diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/trajectory_controller.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/trajectory_controller.py deleted file mode 100644 index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000 diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/intermediate/exercise_1/exercise_1_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/intermediate/exercise_1/exercise_1_1_eval.py deleted file mode 100644 index 89822015c8c269a8c653fd49999e01e9782a7111..0000000000000000000000000000000000000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/intermediate/exercise_1/exercise_1_1_eval.py +++ /dev/null @@ -1 +0,0 @@ -print("TODO: WRITE EVALUATION SCRIPT") \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_4_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_4_eval.py index 89822015c8c269a8c653fd49999e01e9782a7111..a11cfec9eda2041f6af3177844c2186342c4fa94 100644 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_4_eval.py +++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_4_eval.py @@ -1 +1 @@ -print("TODO: WRITE EVALUATION SCRIPT") \ No newline at end of file +print("NO NEED TO EVALUATE THIS SCRIPT") \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb index 936fdb313c6f64c03ea1d037f118db250c61b7d6..ac4628099387cd8fab74cf21e7450a31dff882d2 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.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" ] }, { @@ -15,12 +15,12 @@ "## Controller_Task\n", "### Position_Controller\n", "\n", - "> In this task, you will learn ...\n", + "In this task, you will learn... \n", ">\n", - "> - wie du mit einem Position Controller arbeitest, um die Gelenke eines Roboters auf spezifische Positionen zu bewegen.\n", - "> - wie man den Position Controller startet\n", - "> - wie man eine Nachricht für den Position Controller erstellt\n", - "> - wie man die Zielposition sendt und die Bewegung überprüft" + "> - how to work with a position controller to move the joints of a robot to specific positions.\n", + "> - how to start the position controller\n", + "> - how to create a message for the position controller\n", + "> - how to send the target position and check the movement" ] }, { @@ -34,6 +34,7 @@ "import rospy\n", "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController\n", "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n", + "from moveit_commander import roscpp_shutdown\n", "\n", "##### DO NOT CHANGE #####" ] @@ -42,18 +43,15 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Lade den Controller:\n", + "The following code cell loads and activates a new controller in ROS after a potentially conflicting controller has been unloaded.\n", "\n", - "ROS verwendet den Service /controller_manager/load_controller, um Controller zu laden.\n", - "Du musst den Namen des Controllers angeben, den du laden möchtest, in diesem Fall position_joint_trajectory_controller.\n", - "Aktiviere den Controller:\n", + "First, the new controller and the conflicting controller are defined.\n", "\n", - "Nachdem der Controller geladen ist, musst du ihn starten. Dies geschieht mit dem Service /controller_manager/switch_controller.\n", - "Du kannst mehrere Controller gleichzeitig starten und stoppen, indem du deren Namen in den Service-Request übergibst.\n", - "Verwende die folgende Vorlage:\n", + "Now the conflicting controller will load. First, the /controller_manager/switch_controller service is used to stop the controller. Then the /controller_manager service/unload_controller is used to completely unload. If any of the service calls fail, an error message is issued.\n", "\n", - "Nutze den Service load_controller, um den gewünschten Controller zu laden.\n", - "Starte den Service switch_controller, um den Position Controller zu aktivieren." + "It then waits for the /controller_manager/load_controller service to load the new controller. The service is called and it checks that the controller has been loaded successfully.\n", + "\n", + "Finally, wait for the /controller_manager/switch_controller service to activate the new controller. The service is called and it checks that the controller has been successfully started." ] }, { @@ -64,42 +62,36 @@ "source": [ "##### DO NOT CHANGE #####\n", "\n", - "import rospy\n", - "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController\n", - "\n", "controller_name = 'position_joint_trajectory_controller'\n", "conflicting_controller = 'effort_joint_trajectory_controller'\n", "\n", - "# Funktion zum Entladen eines Controllers\n", - "def unload_controller(controller_name):\n", - " rospy.wait_for_service('/controller_manager/switch_controller')\n", - " try:\n", - " switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", - " req = SwitchControllerRequest()\n", - " req.stop_controllers = [controller_name]\n", - " req.strictness = SwitchControllerRequest.BEST_EFFORT\n", - " response = switch_controller(req)\n", - " assert response.ok, \"Controller konnte nicht entladen werden.\"\n", - " except rospy.ServiceException as e:\n", - " rospy.logerr(\"Service call failed: %s\" % e)\n", - " rospy.wait_for_service('/controller_manager/unload_controller')\n", - " try:\n", - " unload_srv = rospy.ServiceProxy('/controller_manager/unload_controller', UnloadController)\n", - " unload_resp = unload_srv(controller_name)\n", - " assert unload_resp.ok, \"Controller konnte nicht entladen werden.\"\n", - " except rospy.ServiceException as e:\n", - " rospy.logerr(\"Service call failed: %s\" % e)\n", - "\n", - "# Entladen des alten Controllers\n", - "unload_controller(conflicting_controller)\n", - "\n", - "# Service für das Laden des Controllers\n", + "# Service for unloading the conflicting controller\n", + "rospy.wait_for_service('/controller_manager/switch_controller')\n", + "try:\n", + " switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", + " req = SwitchControllerRequest()\n", + " req.stop_controllers = [conflicting_controller]\n", + " req.strictness = SwitchControllerRequest.BEST_EFFORT\n", + " response = switch_controller(req)\n", + " assert response.ok, \"Controller konnte nicht entladen werden.\"\n", + "except rospy.ServiceException as e:\n", + " rospy.logerr(\"Service call failed: %s\" % e)\n", + "\n", + "rospy.wait_for_service('/controller_manager/unload_controller')\n", + "try:\n", + " unload_srv = rospy.ServiceProxy('/controller_manager/unload_controller', UnloadController)\n", + " unload_resp = unload_srv(conflicting_controller)\n", + " assert unload_resp.ok, \"Controller konnte nicht entladen werden.\"\n", + "except rospy.ServiceException as e:\n", + " rospy.logerr(\"Service call failed: %s\" % e)\n", + "\n", + "# Service for loading the controller\n", "rospy.wait_for_service('/controller_manager/load_controller')\n", "load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n", "response = load_service(controller_name)\n", "assert response.ok, \"Controller konnte nicht geladen werden.\"\n", "\n", - "# Service für das Aktivieren des Controllers\n", + "# Sevice for switching the controller\n", "rospy.wait_for_service('/controller_manager/switch_controller')\n", "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", "switch_req = SwitchControllerRequest()\n", @@ -115,25 +107,9 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Nachrichtentyp:\n", - "\n", - "Der Position Controller empfängt Nachrichten vom Typ trajectory_msgs/JointTrajectory.\n", - "Diese Nachricht enthält:\n", - "joint_names: Eine Liste der Gelenke, die gesteuert werden sollen.\n", - "points: Eine Liste von Positionen, die die Gelenke ansteuern sollen.\n", - "Erstelle die Nachricht:\n", + "Now the ROS node is initialized, a publisher is created for the command topic and waited until the publisher is created.\n", "\n", - "Beginne mit einer JointTrajectory-Nachricht.\n", - "Definiere die Gelenke, die du bewegen möchtest, indem du die Namen in der Liste joint_names einträgst.\n", - "Füge Zielpositionen hinzu:\n", - "\n", - "Erstelle ein JointTrajectoryPoint, um die Zielpositionen für jedes Gelenk zu definieren.\n", - "Ergänze die Felder:\n", - "positions: Die Zielpositionen in Radiant (z. B. [0.5, -0.5, 0.0]).\n", - "time_from_start: Die Dauer, die der Roboter benötigt, um die Positionen zu erreichen.\n", - "Sende die Nachricht:\n", - "\n", - "Veröffentliche die Nachricht auf dem Topic /position_joint_trajectory_controller/command." + "The publisher sends messages of the type JointTrajectory to the topic /position_joint_trajectory_controller/command. The parameter queue_size=10 sets the size of the message queue. This means that up to 10 messages are held in the queue before old messages are discarded." ] }, { @@ -153,21 +129,41 @@ "# Warte, bis der Publisher bereit ist\n", "rospy.sleep(1)\n", "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The position controller receives messages of the type trajectory_msgs/JointTrajectory.\n", + "This message contains joint_names, a list of the joints to be controlled, and points, a list of positions to control the joints." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", "# Erstelle die Nachricht\n", "traj_msg = JointTrajectory()\n", "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n", "\n", "# Definiere die Zielpositionen\n", "point = JointTrajectoryPoint()\n", - "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0] # TODO: Füge Zielpositionen (in Radiant) für jedes Gelenk hinzu\n", - "point.time_from_start = rospy.Duration(2.0) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll\n", + "# Hier wird die Zielpositionen (in Radiant) für jedes Gelenk als eine Liste hinzugefügt\n", + "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]\n", + "# Nun wird die Zeit festgelegt, bis die Bewegung abgeschlossen sein soll\n", + "point.time_from_start = rospy.Duration(2.0) \n", "\n", - "# Füge den Punkt zur Trajektorie hinzu\n", + "# Zuletzt wird der Punkt zur Trajektorie hinzugefügt\n", "traj_msg.points.append(point)\n", "\n", - "# Sende die Nachricht\n", + "# und die Nachricht wird gesendet\n", "pub.publish(traj_msg)\n", - "print(\"Zielposition wurde gesendet.\")\n", "\n", "##### DO NOT CHANGE #####" ] @@ -176,23 +172,32 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "In dieser Erweiterung definieren Sie zwei Zielpositionen.\n", - "Die erste Zielposition wird erreicht, bevor der Roboter zur zweiten Zielposition übergeht.\n", - "Was du tun musst:\n", - "\n", - "Füge eine zweite Zielposition zu traj_msg.points hinzu.\n", - "Die zweite Zielposition sollte eine andere Pose ansteuern, um eine sichtbare Bewegung zu demonstrieren.\n", - "Planung der Bewegung:\n", - "\n", - "Verwenden Sie die Zeitsteuerung time_from_start, um sicherzustellen, dass der Roboter genug Zeit hat, die erste Position zu erreichen, bevor er zur nächsten übergeht.\n", - "Die Zeitangaben müssen aufeinander aufbauen:\n", - "Die erste Zielposition benötigt z. B. 2 Sekunden (time_from_start = 2.0).\n", - "Die zweite Zielposition wird nach weiteren 3 Sekunden erreicht (time_from_start = 5.0).\n", - "Schritte:\n", - "\n", - "Erstelle eine erste Zielposition: Definiere die Gelenkwinkel und die Dauer.\n", - "Erstelle eine zweite Zielposition: Erhöhe die Zeit und ändere die Gelenkwinkel.\n", - "Sende beide Punkte: Füge die Punkte zu traj_msg.points hinzu und sende die Nachricht." + "### Task:\n", + "\n", + "Now you have to define two more target positions yourself. We reach the first target position before the robot moves to the second target position.\n", + "\n", + "#### What you need to do:\n", + "\n", + "\n", + "##### Create the message:\n", + "\n", + "Start by creating a JointTrajectory message.\n", + "Next, define the joints you want to move by entering the names in the joint_names list of the JointTrajectory message.\n", + "\n", + "##### Add target positions:\n", + "\n", + "Create a JointTrajectoryPoint to define the target positions for each joint and complete the following fields:\n", + "\n", + "- positions: The target positions in Radiant (e.g. [0.5, -0.5, 0.0])\n", + "\n", + "- time_from_start: The time it takes for the robot to reach the positions\n", + "\n", + "Now add the point to the trajectory and do the same for the second point as for the first.\n", + "\n", + "\n", + "##### Send the message:\n", + "\n", + "Post the message to the topic /position_joint_trajectory_controller/command." ] }, { @@ -221,11 +226,18 @@ "\n", "# Nachricht senden\n", "pub.publish(traj_msg)\n", - "print(\"Zwei Zielpositionen wurden gesendet.\")\n", "\n", "##### YOUR CODE HERE #####" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Cleaning up and quitting the ROS node\n", + "At the end, the ROS node is shut down and the resources are released." + ] + }, { "cell_type": "code", "execution_count": null, diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/trajectory_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/trajectory_controller.ipynb deleted file mode 100644 index 837fa85b1a9af708e1fa894341f21624923d9d56..0000000000000000000000000000000000000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/trajectory_controller.ipynb +++ /dev/null @@ -1,70 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "vscode": { - "languageId": "plaintext" - } - }, - "outputs": [], - "source": [ - "#!/usr/bin/env python\n", - "\n", - "import rospy\n", - "from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryGoal\n", - "from trajectory_msgs.msg import JointTrajectoryPoint\n", - "import actionlib\n", - "\n", - "# ROS-Knoten initialisieren\n", - "rospy.init_node(\"position_controller_example\", anonymous=True)\n", - "\n", - "# Verbindung mit dem Trajectory Controller herstellen\n", - "# Der Code verwendet den ROS-Action-Server /panda_arm_controller/follow_joint_trajectory, um Gelenkpositionen anzusteuern.\n", - "# Diese Schnittstelle basiert auf dem Trajectory Controller, der für die präzise Steuerung von Gelenkbewegungen zuständig ist.\n", - "\n", - "client = actionlib.SimpleActionClient('/panda_arm_controller/follow_joint_trajectory', FollowJointTrajectoryAction)\n", - "rospy.loginfo(\"Waiting for trajectory controller...\")\n", - "client.wait_for_server()\n", - "rospy.loginfo(\"Connected to trajectory controller!\")\n", - "\n", - "# Zielgelenkpositionen definieren\n", - "joint_goal = [0.0, -0.785, 0.0, -2.356, 0.0, 1.57, 0.785]\n", - "\n", - "# Trajektorie erstellen\n", - "goal = FollowJointTrajectoryGoal()\n", - "goal.trajectory.joint_names = [\n", - " \"panda_joint1\", \"panda_joint2\", \"panda_joint3\",\n", - " \"panda_joint4\", \"panda_joint5\", \"panda_joint6\", \"panda_joint7\"\n", - "]\n", - "\n", - "point = JointTrajectoryPoint()\n", - "point.positions = joint_goal\n", - "point.time_from_start = rospy.Duration(5.0) # Die Bewegung soll in 5 Sekunden abgeschlossen sein\n", - "\n", - "goal.trajectory.points.append(point)\n", - "goal.trajectory.header.stamp = rospy.Time.now()\n", - "\n", - "# Ziel senden\n", - "rospy.loginfo(\"Sending goal to trajectory controller...\")\n", - "client.send_goal(goal)\n", - "client.wait_for_result()\n", - "\n", - "# Ergebnis überprüfen\n", - "result = client.get_result()\n", - "if result:\n", - " rospy.loginfo(\"Trajectory successfully executed!\")\n", - "else:\n", - " rospy.logwarn(\"Failed to execute trajectory.\")" - ] - } - ], - "metadata": { - "language_info": { - "name": "python" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/intermediate/exercise_1/exercise_1_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/intermediate/exercise_1/exercise_1_1.ipynb deleted file mode 100644 index 58b1a817c8d478bbfebd2b77615974659e968a34..0000000000000000000000000000000000000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/intermediate/exercise_1/exercise_1_1.ipynb +++ /dev/null @@ -1,212 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "TODO: FORMAT AS NOTEBOOK" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "vscode": { - "languageId": "plaintext" - } - }, - "outputs": [], - "source": [ - "import rospy\n", - "from moveit_commander import PlanningSceneInterface, MoveGroupCommander\n", - "from moveit_msgs.msg import Grasp, PlaceLocation, CollisionObject\n", - "from geometry_msgs.msg import PoseStamped, Pose\n", - "from tf.transformations import quaternion_from_euler\n", - "from shape_msgs.msg import SolidPrimitive\n", - "import moveit_msgs\n", - "import shape_msgs\n", - "import geometry_msgs\n", - "import trajectory_msgs\n", - "\n", - "def create_collision_objects(planning_scene_interface):\n", - " # Tabelle 1\n", - " table1 = moveit_msgs.msg.CollisionObject()\n", - " table1.id = \"table1\"\n", - " table1.header.frame_id = \"panda_link0\"\n", - "\n", - " primitive1 = shape_msgs.msg.SolidPrimitive()\n", - " primitive1.type = shape_msgs.msg.SolidPrimitive.BOX\n", - " primitive1.dimensions = [0.2, 0.4, 0.4] # Länge, Breite, Höhe\n", - "\n", - " table1.primitives.append(primitive1)\n", - "\n", - " pose1 = geometry_msgs.msg.Pose()\n", - " pose1.position.x = 0.5\n", - " pose1.position.y = 0.0\n", - " pose1.position.z = 0.2\n", - " pose1.orientation.w = 1.0\n", - "\n", - " table1.primitive_poses.append(pose1)\n", - " table1.operation = moveit_msgs.msg.CollisionObject.ADD\n", - "\n", - " # Füge Tabelle 1 hinzu\n", - " planning_scene_interface.add_object(table1)\n", - "\n", - " # Tabelle 2\n", - " table2 = moveit_msgs.msg.CollisionObject()\n", - " table2.id = \"table2\"\n", - " table2.header.frame_id = \"panda_link0\"\n", - "\n", - " primitive2 = shape_msgs.msg.SolidPrimitive()\n", - " primitive2.type = shape_msgs.msg.SolidPrimitive.BOX\n", - " primitive2.dimensions = [0.4, 0.2, 0.4]\n", - "\n", - " table2.primitives.append(primitive2)\n", - "\n", - " pose2 = geometry_msgs.msg.Pose()\n", - " pose2.position.x = 0.0\n", - " pose2.position.y = 0.5\n", - " pose2.position.z = 0.2\n", - " pose2.orientation.w = 1.0\n", - "\n", - " table2.primitive_poses.append(pose2)\n", - " table2.operation = moveit_msgs.msg.CollisionObject.ADD\n", - "\n", - " # Füge Tabelle 2 hinzu\n", - " planning_scene_interface.add_object(table2)\n", - "\n", - " # Zielobjekt\n", - " target_object = moveit_msgs.msg.CollisionObject()\n", - " target_object.id = \"object\"\n", - " target_object.header.frame_id = \"panda_link0\"\n", - "\n", - " primitive3 = shape_msgs.msg.SolidPrimitive()\n", - " primitive3.type = shape_msgs.msg.SolidPrimitive.BOX\n", - " primitive3.dimensions = [0.02, 0.02, 0.2]\n", - "\n", - " target_object.primitives.append(primitive3)\n", - "\n", - " pose3 = geometry_msgs.msg.Pose()\n", - " pose3.position.x = 0.5\n", - " pose3.position.y = 0.0\n", - " pose3.position.z = 0.5\n", - " pose3.orientation.w = 1.0\n", - "\n", - " target_object.primitive_poses.append(pose3)\n", - " target_object.operation = moveit_msgs.msg.CollisionObject.ADD\n", - "\n", - " # Füge Zielobjekt hinzu\n", - " planning_scene_interface.add_object(target_object)\n", - "\n", - "def open_gripper():\n", - " \"\"\"Define the gripper open position.\"\"\"\n", - " posture = {\"joint_names\": [\"panda_finger_joint1\", \"panda_finger_joint2\"],\n", - " \"points\": [{\"positions\": [0.04, 0.04], \"time_from_start\": rospy.Duration(0.5)}]}\n", - " return posture\n", - "\n", - "def close_gripper():\n", - " \"\"\"Define the gripper closed position.\"\"\"\n", - " posture = {\"joint_names\": [\"panda_finger_joint1\", \"panda_finger_joint2\"],\n", - " \"points\": [{\"positions\": [0.0, 0.0], \"time_from_start\": rospy.Duration(0.5)}]}\n", - " return posture\n", - "\n", - "def pick(move_group):\n", - " # Erstelle ein Grasp-Objekt\n", - " grasp = moveit_msgs.msg.Grasp()\n", - "\n", - " # Grasp Pose: Wo der Roboter das Objekt greifen soll\n", - " grasp.grasp_pose.header.frame_id = \"panda_link0\"\n", - " grasp.grasp_pose.pose.position.x = 0.5\n", - " grasp.grasp_pose.pose.position.y = 0.0\n", - " grasp.grasp_pose.pose.position.z = 0.5\n", - " grasp.grasp_pose.pose.orientation.w = 1.0\n", - "\n", - " # Pre-Grasp Approach: Bewegung zum Greifen\n", - " grasp.pre_grasp_approach.direction.header.frame_id = \"panda_link0\"\n", - " grasp.pre_grasp_approach.direction.vector.z = -1.0 # Bewegung entlang der -z-Achse\n", - " grasp.pre_grasp_approach.min_distance = 0.095\n", - " grasp.pre_grasp_approach.desired_distance = 0.115\n", - "\n", - " # Post-Grasp Retreat: Bewegung nach dem Greifen\n", - " grasp.post_grasp_retreat.direction.header.frame_id = \"panda_link0\"\n", - " grasp.post_grasp_retreat.direction.vector.z = 1.0 # Bewegung entlang der +z-Achse\n", - " grasp.post_grasp_retreat.min_distance = 0.1\n", - " grasp.post_grasp_retreat.desired_distance = 0.25\n", - "\n", - " # Pre-Grasp Posture: Öffne den Greifer\n", - " grasp.pre_grasp_posture.joint_names = [\"panda_finger_joint1\", \"panda_finger_joint2\"]\n", - " grasp.pre_grasp_posture.points = [\n", - " trajectory_msgs.msg.JointTrajectoryPoint(\n", - " positions=[0.04, 0.04], time_from_start=rospy.Duration(0.5)\n", - " )\n", - " ]\n", - "\n", - " # Grasp Posture: Schließe den Greifer\n", - " grasp.grasp_posture.joint_names = [\"panda_finger_joint1\", \"panda_finger_joint2\"]\n", - " grasp.grasp_posture.points = [\n", - " trajectory_msgs.msg.JointTrajectoryPoint(\n", - " positions=[0.0, 0.0], time_from_start=rospy.Duration(0.5)\n", - " )\n", - " ]\n", - "\n", - " # Führe den Greifvorgang aus\n", - " move_group.pick(\"object\", [grasp])\n", - "\n", - "def place(move_group):\n", - " # Erstelle ein PlaceLocation-Objekt\n", - " place_location = moveit_msgs.msg.PlaceLocation()\n", - "\n", - " # Setze die Zielpose für das Platzieren\n", - " place_location.place_pose.header.frame_id = \"panda_link0\"\n", - " place_location.place_pose.pose.position.x = 0.0\n", - " place_location.place_pose.pose.position.y = 0.5\n", - " place_location.place_pose.pose.position.z = 0.5\n", - " place_location.place_pose.pose.orientation.w = 1.0\n", - "\n", - " # Pre-Place Approach: Bewegung vor dem Platzieren\n", - " place_location.pre_place_approach.direction.header.frame_id = \"panda_link0\"\n", - " place_location.pre_place_approach.direction.vector.z = -1.0 # Bewegung entlang der -z-Achse\n", - " place_location.pre_place_approach.min_distance = 0.095\n", - " place_location.pre_place_approach.desired_distance = 0.115\n", - "\n", - " # Post-Place Retreat: Bewegung nach dem Platzieren\n", - " place_location.post_place_retreat.direction.header.frame_id = \"panda_link0\"\n", - " place_location.post_place_retreat.direction.vector.y = -1.0 # Bewegung entlang der -y-Achse\n", - " place_location.post_place_retreat.min_distance = 0.1\n", - " place_location.post_place_retreat.desired_distance = 0.25\n", - "\n", - " # Post-Place Posture: Öffne den Greifer\n", - " place_location.post_place_posture.joint_names = [\"panda_finger_joint1\", \"panda_finger_joint2\"]\n", - " place_location.post_place_posture.points = [\n", - " trajectory_msgs.msg.JointTrajectoryPoint(\n", - " positions=[0.04, 0.04], time_from_start=rospy.Duration(0.5)\n", - " )\n", - " ]\n", - "\n", - " # Führe den Platzierungsvorgang aus\n", - " move_group.place(\"object\", [place_location])\n", - " \n", - "if __name__ == \"__main__\":\n", - " rospy.init_node(\"pick_place_tutorial\", anonymous=True)\n", - " planning_scene_interface = PlanningSceneInterface()\n", - " move_group = MoveGroupCommander(\"panda_arm\")\n", - " move_group.set_planning_time(45.0)\n", - "\n", - " create_collision_objects(planning_scene_interface)\n", - " rospy.sleep(2)\n", - "\n", - " pick(move_group)\n", - " rospy.sleep(2)\n", - "\n", - " place(move_group)" - ] - } - ], - "metadata": { - "language_info": { - "name": "python" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb index 9a4f3c54b602804edb74a5bc4d24ddad5a4f6802..f09cc2622ad9a71b0a9e2c42fad839f80348ad9e 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb @@ -63,7 +63,10 @@ "First, we import all the important modules for this task. You already know Rospy and sys from previous tasks.\n", "The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements.\n", "roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API.\n", - "geometry_msgs.msg is used to provide standardized message formats such as position(pose) and orientation (point) of the robotic arm." + "\n", + "geometry_msgs.msg is used to provide standardized message formats such as position (Point) and orientation (Quaternion) of the robotic arm.\n", + "\n", + "The pose class now represents a combination of position (point) and orientation (quaternion) to describe a pose (position and orientation) in 3D space." ] }, { @@ -95,7 +98,9 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Next, we want to select the planning algorithm we want to use to calculate the motion. To do this, we use the set_planner_id method to select the specific planning algorithm." + "Next, we want to select the planning algorithm we want to use to calculate the motion. To do this, we use the set_planner_id method to select the specific planning algorithm.\n", + "\n", + "Next, your task is to select the planning algorithm with the ID RRTConnectkConfigDefault for the previously defined MoveGroupCommander instance." ] }, { @@ -119,12 +124,15 @@ "Next, we define the target position of the end effector. The end effector is the part of a robot arm that is attached to the extreme end of the kinematic chain and directly interacts with the environment. It is the functional \"tool holder\" of the robot, whose job it is to perform specific actions. These actions depend heavily on the task of the robot.\n", "\n", "The pose class provides a data structure that describes the spatial position and orientation of an object in 3D space. The position contains the x-, y- and z-coordinates, which in the following code defines the target position of the end effector in Cartesian space (in meters).\n", - "The orientation w describes the orientation, which is used for orientation in 3D space.\n", + "The orientation is represented by a quaternion, where the w component describes the rotation around the axis.\n", + "\n", + "Your task now is to define a new pose, which has the point (0.1, 0.1, 0.1) and the orientation 1 (neutral).\n", "\n", - "A w=cos(θ/2) that is less than 1 indicates that a rotation is taking place.\n", - "The rotation angle θ can be calculated via arccos(w)⋆2.\n", + "Procedure:\n", "\n", - "w should always be in the range [−1.1] because it is related to cos(θ/2). Values outside this range result in invalid quaternions." + "- 1. Create a new object of type Pose\n", + "- 2. Set the variables for the position\n", + "- 3. Set the required variables for the orientation" ] }, { diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb index 1e7b41a5e9fe63fac0da224f94e0390f5d492ca4..6492b6e6cbe26efb03c0ec02d6943e49e49f78d0 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb @@ -110,6 +110,8 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "# rectangle_1\n", "rectangle_1 = CollisionObject()\n", "rectangle_1.id = \"rectangle_1\"\n", @@ -131,7 +133,9 @@ "rectangle_1.operation = CollisionObject.ADD\n", "\n", "# add rectangle_1 to the planning scene\n", - "planning_scene_interface.add_object(rectangle_1)" + "planning_scene_interface.add_object(rectangle_1)\n", + "\n", + "##### YOUR CODE HERE #####" ] }, { @@ -160,6 +164,8 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "# rectangle_2\n", "rectangle_2 = CollisionObject()\n", "rectangle_2.id = \"rectangle_2\"\n", @@ -181,7 +187,9 @@ "rectangle_2.operation = CollisionObject.ADD\n", "\n", "# add rectangle_2 to the planning scene\n", - "planning_scene_interface.add_object(rectangle_2)" + "planning_scene_interface.add_object(rectangle_2)\n", + "\n", + "##### YOUR CODE HERE #####" ] }, { @@ -210,6 +218,8 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "# target_object\n", "target_object = CollisionObject()\n", "target_object.id = \"target\"\n", @@ -231,7 +241,9 @@ "target_object.operation = CollisionObject.ADD\n", "\n", "# add target_object to the planning scene\n", - "planning_scene_interface.add_object(target_object)" + "planning_scene_interface.add_object(target_object)\n", + "\n", + "##### YOUR CODE HERE #####" ] }, { diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb index 8bb63b99a8723f6d7254d5231e097f14ab066fcf..90cc9abd2f32d92cd7855d4fe95aeeacf1bab37f 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb @@ -116,12 +116,12 @@ "metadata": {}, "outputs": [], "source": [ - "##### WRITE YOUR CODE HERE #####\n", + "##### YOUR CODE HERE #####\n", "\n", "object_names = scene.get_known_object_names()\n", "rospy.loginfo(len(object_names) == 0)\n", "\n", - "##### WRITE YOUR CODE HERE #####" + "##### YOUR CODE HERE #####" ] }, { 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 7e6d9457be42767121554e7e51322ce4db3c13d3..901fb038802df1bfc254cabb8e184527428a77e3 100644 --- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json +++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json @@ -132,31 +132,11 @@ "subtasks": [ { "title": "Task 1", - "description": "Understand the basics of the trajectory controller", - "solution_file": "/trajectory_controller.ipynb", - "evaluation_file": "/trajectory_controller.py" - }, - { - "title": "Task 2", "description": "Undersatnd the basics of the position controller", "solution_file": "/position_controller.ipynb", "evaluation_file": "/position_controller.py" } ] - }, - { - "title": "Task 7 (TODO: Rename)", - "topic": "fjdsfkl", - "difficulty": "intermediate", - "folder": "/intermediate/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" - } - ] } ] } \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb index 8a843dbdd88625b2f8b22550fc896baf5d83e340..7670df82394d942550e073cdf763f47fce90c9e0 100644 --- a/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb +++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb @@ -118,12 +118,12 @@ "outputs": [], "source": [ "##############################################################\n#### THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE. ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n#### USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE. ####\n##############################################################\n\n", - "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n", + "##### DO NOT CHANGE #####\n", "\n", - "# Get the current pose of the end-effector\n", - "current_pose = group.get_current_pose().pose\n", + "# Define the waypoints the robot should move to\n", + "waypoints = []\n", "\n", - "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##" + "##### DO NOT CHANGE #####" ] }, { @@ -192,12 +192,12 @@ "##############################################################\n#### THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE. ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n#### USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE. ####\n##############################################################\n\n", "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n", "\n", - "waypoint_1 = Pose()\n", - "waypoint_1.position.x = current_pose.position.x + 0.1\n", - "waypoint_1.position.y = current_pose.position.y\n", - "waypoint_1.position.z = current_pose.position.z\n", - "waypoint_1.orientation = current_pose.orientation\n", - "waypoints.append(waypoint_1)\n", + "waypoint_2 = Pose()\n", + "waypoint_2.position.x = waypoint_1.position.x\n", + "waypoint_2.position.y = waypoint_1.position.y + 0.2\n", + "waypoint_2.position.z = waypoint_1.position.z\n", + "waypoint_2.orientation = current_pose.orientation\n", + "waypoints.append(waypoint_2)\n", "\n", "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##" ] @@ -242,12 +242,12 @@ "##############################################################\n#### THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE. ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n#### USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE. ####\n##############################################################\n\n", "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n", "\n", - "waypoint_2 = Pose()\n", - "waypoint_2.position.x = waypoint_1.position.x\n", - "waypoint_2.position.y = waypoint_1.position.y + 0.2\n", - "waypoint_2.position.z = waypoint_1.position.z\n", - "waypoint_2.orientation = current_pose.orientation\n", - "waypoints.append(waypoint_2)\n", + "waypoint_3 = Pose()\n", + "waypoint_3.position.x = waypoint_2.position.x\n", + "waypoint_3.position.y = waypoint_2.position.y\n", + "waypoint_3.position.z = waypoint_2.position.z + 0.3\n", + "waypoint_3.orientation = current_pose.orientation\n", + "waypoints.append(waypoint_3)\n", "\n", "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##" ] @@ -290,16 +290,14 @@ "outputs": [], "source": [ "##############################################################\n#### THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE. ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n#### USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE. ####\n##############################################################\n\n", - "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n", + "##### DO NOT CHANGE #####\n", "\n", - "waypoint_3 = Pose()\n", - "waypoint_3.position.x = waypoint_2.position.x\n", - "waypoint_3.position.y = waypoint_2.position.y\n", - "waypoint_3.position.z = waypoint_2.position.z + 0.4\n", - "waypoint_3.orientation = current_pose.orientation\n", - "waypoints.append(waypoint_3)\n", + "# Compute the Cartesian path\n", + "fraction = 0.0\n", + "max_attempts = 100\n", + "attempts = 0\n", "\n", - "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##" + "##### DO NOT CHANGE #####" ] }, { @@ -372,13 +370,14 @@ "outputs": [], "source": [ "##############################################################\n#### THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE. ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n#### USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE. ####\n##############################################################\n\n", - "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n", + "##### DO NOT CHANGE #####\n", "\n", - "while fraction < 1.0 and attempts < max_attempts:\n", - " (plan, fraction) = group.compute_cartesian_path(waypoints, 0.01, 0.0) # Plan the trajectory\n", - " attempts += 1\n", + "if fraction == 1.0:\n", + " group.execute(plan, wait=True)\n", + "else:\n", + " rospy.logwarn(f\"Failed to compute a complete path after {attempts} attempts.\")\n", "\n", - "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##" + "##### DO NOT CHANGE #####" ] }, {