From 1dd5092d971b5ce8583dd3f3192f083ec62eb420 Mon Sep 17 00:00:00 2001 From: uninh <uninh@student.kit.edu> Date: Fri, 20 Dec 2024 13:59:44 +0000 Subject: [PATCH] changed structure of tasks --- .../move_it_basics/move_it_basics_3_eval.py} | 0 .../move_it_basics/move_it_basics_4_eval.py} | 0 .../move_it_objects_1_eval.py} | 0 .../move_it_objects_2_eval.py} | 0 .../move_it_objects_3_eval.py} | 0 .../move_it_basics/move_it_basics_3.ipynb} | 19 +- .../move_it_basics/move_it_basics_4.ipynb} | 21 +- .../move_it_objects/move_it_objects_1.ipynb} | 8 +- .../move_it_objects/move_it_objects_2.ipynb} | 7 +- .../move_it_objects/move_it_objects_3.ipynb} | 4 +- .../task_pool/task_definitions.json | 70 ++-- .../move_it_basics/move_it_basics_3.ipynb | 222 ++++++++++++ .../move_it_basics/move_it_basics_4.ipynb | 192 +++++++++++ .../move_it_objects/move_it_objects_1.ipynb | 316 ++++++++++++++++++ .../move_it_objects/move_it_objects_2.ipynb | 292 ++++++++++++++++ .../move_it_objects/move_it_objects_3.ipynb | 172 ++++++++++ 16 files changed, 1268 insertions(+), 55 deletions(-) rename catkin_ws/src/learn_environment/task_pool/evaluation_scripts/{beginner/exercise_4/exercise_4_1_eval.py => move_it/move_it_basics/move_it_basics_3_eval.py} (100%) rename catkin_ws/src/learn_environment/task_pool/evaluation_scripts/{beginner/exercise_4/exercise_4_2_eval.py => move_it/move_it_basics/move_it_basics_4_eval.py} (100%) rename catkin_ws/src/learn_environment/task_pool/evaluation_scripts/{beginner/exercise_5/exercise_5_1_eval.py => move_it/move_it_objects/move_it_objects_1_eval.py} (100%) rename catkin_ws/src/learn_environment/task_pool/evaluation_scripts/{beginner/exercise_5/exercise_5_2_eval.py => move_it/move_it_objects/move_it_objects_2_eval.py} (100%) rename catkin_ws/src/learn_environment/task_pool/evaluation_scripts/{beginner/exercise_5/exercise_5_3_eval.py => move_it/move_it_objects/move_it_objects_3_eval.py} (100%) rename catkin_ws/src/learn_environment/task_pool/solution_scripts/{beginner/exercise_4/exercise_4_1.ipynb => move_it/move_it_basics/move_it_basics_3.ipynb} (94%) rename catkin_ws/src/learn_environment/task_pool/solution_scripts/{beginner/exercise_4/exercise_4_2.ipynb => move_it/move_it_basics/move_it_basics_4.ipynb} (92%) rename catkin_ws/src/learn_environment/task_pool/solution_scripts/{beginner/exercise_5/exercise_5_1.ipynb => move_it/move_it_objects/move_it_objects_1.ipynb} (98%) rename catkin_ws/src/learn_environment/task_pool/solution_scripts/{beginner/exercise_5/exercise_5_3.ipynb => move_it/move_it_objects/move_it_objects_2.ipynb} (98%) rename catkin_ws/src/learn_environment/task_pool/solution_scripts/{beginner/exercise_5/exercise_5_2.ipynb => move_it/move_it_objects/move_it_objects_3.ipynb} (98%) create mode 100644 catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_3.ipynb create mode 100644 catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_4.ipynb create mode 100644 catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_1.ipynb create mode 100644 catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_2.ipynb create mode 100644 catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_3.ipynb diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_4/exercise_4_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_3_eval.py similarity index 100% rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_4/exercise_4_1_eval.py rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_3_eval.py diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_4/exercise_4_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_4_eval.py similarity index 100% rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_4/exercise_4_2_eval.py rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_4_eval.py diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_5/exercise_5_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_objects/move_it_objects_1_eval.py similarity index 100% rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_5/exercise_5_1_eval.py rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_objects/move_it_objects_1_eval.py diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_5/exercise_5_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_objects/move_it_objects_2_eval.py similarity index 100% rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_5/exercise_5_2_eval.py rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_objects/move_it_objects_2_eval.py diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_5/exercise_5_3_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_objects/move_it_objects_3_eval.py similarity index 100% rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_5/exercise_5_3_eval.py rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_objects/move_it_objects_3_eval.py diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_4/exercise_4_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb similarity index 94% rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_4/exercise_4_1.ipynb rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb index b007f03..5be619c 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_4/exercise_4_1.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb @@ -6,15 +6,16 @@ "source": [ "# Educational Plattform Franka Emika Panda robot arm\n", "\n", - "Author: uninh, uqwfa, ultck\n", - "\n", - "### Exercise_4_1 :" + "Author: uninh, uqwfa, ultck" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ + "## MoveIt Basics\n", + "### Task 3\n", + "\n", "---\n", ">\n", "The goal of this notebook is: \n", @@ -103,8 +104,12 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "# Select the desired planning algorithm\n", - "group.set_planner_id(\"RRTConnectkConfigDefault\")" + "group.set_planner_id(\"RRTConnectkConfigDefault\")\n", + "\n", + "##### YOUR CODE HERE #####" ] }, { @@ -128,11 +133,15 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "target_pose = Pose()\n", "target_pose.position.x = 0.1\n", "target_pose.position.y = 0.1\n", "target_pose.position.z = 0.1\n", - "target_pose.orientation.w = 1.0" + "target_pose.orientation.w = 1.0\n", + "\n", + "##### YOUR CODE HERE #####" ] }, { diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_4/exercise_4_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb similarity index 92% rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_4/exercise_4_2.ipynb rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb index dc91d67..172f8b9 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_4/exercise_4_2.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb @@ -6,20 +6,21 @@ "source": [ "# Educational Plattform Franka Emika Panda robot arm\n", "\n", - "Author: uninh, uqwfa, ultck\n", - "\n", - "### Exercise_4_2 :" + "Author: uninh, uqwfa, ultck" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ + "## MoveIt Basics\n", + "### Task 4\n", + "\n", "---\n", "> \n", "The goal of this notebook is: \n", "- query and interpret the status of the Franka Emika Panda robotic arm. \n", - "- check the current state of the robot (positions, orientations, > joint angle) and understand how to access feedback during or after a movement.\n", + "- check the current state of the robot (positions, orientations, joint angle) and understand how to access feedback during or after a movement.\n", ">\n", "---" ] @@ -98,11 +99,15 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "# Query the current joint values\n", "joint_values = group.get_current_joint_values() \n", "rospy.loginfo(\"Current Joint Values: \")\n", "for i, joint in enumerate(joint_values):\n", - " rospy.loginfo(f\"Joint {i+1}: {joint:.2f} rad\")" + " rospy.loginfo(f\"Joint {i+1}: {joint:.2f} rad\")\n", + "\n", + "##### YOUR CODE HERE #####" ] }, { @@ -123,10 +128,14 @@ "metadata": {}, "outputs": [], "source": [ + "##### YOUR CODE HERE #####\n", + "\n", "# Query the current end-effector pose\n", "pose = group.get_current_pose().pose\n", "rospy.loginfo(f\"Endeffector Position: x={pose.position.x:.3f}, y={pose.position.y:.3f}, z={pose.position.z:.3f}\")\n", - "rospy.loginfo(f\"Endeffector Orientation: x={pose.orientation.x:.3f}, y={pose.orientation.y:.3f}, z={pose.orientation.z:.3f}, w={pose.orientation.w:.3f}\")\n" + "rospy.loginfo(f\"Endeffector Orientation: x={pose.orientation.x:.3f}, y={pose.orientation.y:.3f}, z={pose.orientation.z:.3f}, w={pose.orientation.w:.3f}\")\n", + "\n", + "##### YOUR CODE HERE #####\n" ] }, { diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb similarity index 98% rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_1.ipynb rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb index 104e7a7..dc86c08 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_1.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb @@ -6,16 +6,16 @@ "source": [ "# Educational Plattform Franka Emika Panda robot arm\n", "\n", - "Author: uninh, uqwfa, ultck\n", - "\n", - "### Exercise_5_1 :\n", - "\n" + "Author: uninh, uqwfa, ultck" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ + "## MoveIt Objects\n", + "### Task 1\n", + "\n", "---\n", ">\n", "The goal of this notebook is:\n", diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb similarity index 98% rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_3.ipynb rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb index 509aea5..f71e067 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_3.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb @@ -6,15 +6,16 @@ "source": [ "# Educational Plattform Franka Emika Panda robot arm\n", "\n", - "Author: uninh, uqwfa, ultck\n", - "\n", - "### Exercise_5_3 :" + "Author: uninh, uqwfa, ultck" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ + "## MoveIt Objects\n", + "### Task 2\n", + "\n", "---\n", ">\n", "The goal of this notebook is:\n", diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb similarity index 98% rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_2.ipynb rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb index 0a5c968..1e5d387 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_5/exercise_5_2.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb @@ -5,6 +5,7 @@ "metadata": {}, "source": [ "# Educational Plattform Panda Robot\n", + "\n", "Author: uninh, uqwfa, ultck" ] }, @@ -12,7 +13,8 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "### Exercise_5_2\n", + "## MoveIt Objects\n", + "### Task 3\n", "\n", "---\n", "> \n", diff --git a/catkin_ws/src/learn_environment/task_pool/task_definitions.json b/catkin_ws/src/learn_environment/task_pool/task_definitions.json index c6b804c..812d073 100644 --- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json +++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json @@ -69,60 +69,58 @@ "description": "Implement a simple movement with MoveIt.", "solution_file": "/move_it_basics_2.ipynb", "evaluation_file": "/move_it_basics_2_eval.py" - } - ] - }, - { - "title": "Trajectory Controller", - "folder": "/controller/controller_task", - "topic": "Controller", - "difficulty": "beginner", - "subtasks": [ + }, { - "title": "Task 1", - "description": "TODO: Add Subtask Description Subtask 1.", - "solution_file": "/trajectory_controller.ipynb", - "evaluation_file": "/trajectory_controller.py" + "title": "Task 3 ", + "description": "Introduction to planning algorithms", + "solution_file": "/move_it_basics_3.ipynb", + "evaluation_file": "/move_it_basics_3_eval.py" + }, + { + "title": "Task 4 ", + "description": "Query and interpret the status of the robotic arm", + "solution_file": "/move_it_basics_4.ipynb", + "evaluation_file": "/move_it_basics_4_eval.py" } ] }, { - "title": "Task 4 (TODO: Rename)", - "topic": "Topic 3", + "title": "MoveIt Objects", + "folder": "/move_it/move_it_objects", + "topic": "MoveIt", "difficulty": "beginner", - "folder": "/beginner/exercise_4", "subtasks": [ { - "title": "Subtask 4.1 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 1.", - "solution_file": "/exercise_4_1.ipynb", - "evaluation_file": "/exercise_4_1_eval.py" + "title": "Task 1 ", + "description": "Create an object in moveit", + "solution_file": "/move_it_objects_1.ipynb", + "evaluation_file": "/move_it_objects_1_eval.py" }, { - "title": "Subtask 4.2 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 2.", - "solution_file": "/exercise_4_2.ipynb", - "evaluation_file": "/exercise_4_2_eval.py" + "title": "Task 2 ", + "description": "Get to know new classes for creating objects", + "solution_file": "/move_it_objects_2.ipynb", + "evaluation_file": "/move_it_objects_2_eval.py" + }, + { + "title": "Task 3 ", + "description": "Understand how to remove objects from a scene", + "solution_file": "/move_it_objects_3.ipynb", + "evaluation_file": "/move_it_objects_3_eval.py" } ] }, { - "title": "Task 5 (TODO: Rename)", - "topic": "Topic 2", + "title": "Trajectory Controller", + "folder": "/controller/controller_task", + "topic": "Controller", "difficulty": "beginner", - "folder": "/beginner/exercise_5", "subtasks": [ { - "title": "Subtask 5.1 (TODO: Rename)", + "title": "Task 1", "description": "TODO: Add Subtask Description Subtask 1.", - "solution_file": "/exercise_5_1.ipynb", - "evaluation_file": "/exercise_5_1_eval.py" - }, - { - "title": "Subtask 5.2 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 2.", - "solution_file": "/exercise_5_2.ipynb", - "evaluation_file": "/exercise_5_2_eval.py" + "solution_file": "/trajectory_controller.ipynb", + "evaluation_file": "/trajectory_controller.py" } ] }, diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_3.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_3.ipynb new file mode 100644 index 0000000..1ea1023 --- /dev/null +++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_3.ipynb @@ -0,0 +1,222 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Educational Plattform Franka Emika Panda robot arm\n", + "\n", + "Author: uninh, uqwfa, ultck" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MoveIt Basics\n", + "### Task 3\n", + "\n", + "---\n", + ">\n", + "The goal of this notebook is: \n", + "- understand what planning algorithms are\n", + "- what types there are\n", + "- how to implement them in code\n", + ">\n", + "---\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Introduction planning algorithms\n", + "\n", + "#### What are planning algorithms?\n", + "\n", + "- Methods used to calculate a sequence of movements or actions that the robot must perform in order to reach a target (e.g. a final position)\n", + "- help solve complex problems, such as overcoming obstacles, precise reaching of endpoint\n", + "- ensure that movement is efficient, collision-free and physically possible\n", + "\n", + "#### What types of planning algorithms are there ?\n", + "\n", + "Sampling-based algorithms\n", + "\n", + "- create random sample to find way from start to finish\n", + "- Examples: RTT, RTTConnect\n", + "\n", + "##### Search-based algorithms\n", + "\n", + "- use grids or graphs to calculate shortest path\n", + "- Example: A*\n", + "\n", + "##### Optimization based algorithms\n", + "\n", + "- improve existing paths through optimization criteria, such as efficiency\n", + "- Examples: CHOMP, STOMP" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "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." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_1" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import rospy\n", + "import sys\n", + "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n", + "from geometry_msgs.msg import Pose\n", + "\n", + "# Initialize the MoveIt Commander\n", + "roscpp_initialize(sys.argv)\n", + "\n", + "# Initialize the ROS Node\n", + "rospy.init_node('exercise_4_1', anonymous=True)\n", + "\n", + "# Initialize MoveGroupCommander\n", + "group = MoveGroupCommander('panda_arm')\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "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." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_2", + "solution_removed_cell" + ] + }, + "outputs": [], + "source": [ + "##### YOUR CODE HERE #####\n", + "raise NotImplementedError()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "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", + "\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", + "\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." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_3", + "solution_removed_cell" + ] + }, + "outputs": [], + "source": [ + "##### YOUR CODE HERE #####\n", + "raise NotImplementedError()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now it's about planning and executing the movement of the robotic arm.\n", + "\n", + "The group.go() method executes the planned movement of the robot based on the target pose that was previously set.\n", + "\n", + "The wait=True argument means that further execution of the code is blocked (i.e. waits) until the movement is complete. Only after the movement is completed will the next command be executed.\n", + "\n", + "The group.stop() method stops the movement of the robot immediately.\n", + "Even if the movement is already complete, this command ensures that no further movements or residual movements (e.g. by inertia or revival) take place.\n", + "\n", + "The group.clear_pose_targets() method removes all pose targets previously defined for the robot.\n", + "\n", + "This is very important because target positions that are not removed remain in the memory of the MoveIt object (group) and could be reused inadvertently in later move commands." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_4" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "plan = group.go(wait=True)\n", + "group.stop()\n", + "group.clear_pose_targets()\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "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, + "metadata": { + "tags": [ + "task_cell_5" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Shutdown the ROS node\n", + "rospy.signal_shutdown(\"Task completed\")\n", + "roscpp_shutdown()\n", + "\n", + "##### DO NOT CHANGE #####" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_4.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_4.ipynb new file mode 100644 index 0000000..bbbbe6d --- /dev/null +++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_4.ipynb @@ -0,0 +1,192 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Educational Plattform Franka Emika Panda robot arm\n", + "\n", + "Author: uninh, uqwfa, ultck" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MoveIt Basics\n", + "### Task 4\n", + "\n", + "---\n", + "> \n", + "The goal of this notebook is: \n", + "- query and interpret the status of the Franka Emika Panda robotic arm. \n", + "- check the current state of the robot (positions, orientations, joint angle) and understand how to access feedback during or after a movement.\n", + ">\n", + "---" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "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." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_1" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import rospy\n", + "import sys\n", + "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n", + "\n", + "# Initialize the MoveIt Commander\n", + "roscpp_initialize(sys.argv)\n", + "\n", + "# Initialize the ROS Node\n", + "rospy.init_node('exercise_4_2', anonymous=True)\n", + "\n", + "##### DO NOT CHANGE #####\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now the MoveGroup for the robot arm `panda_arm` is initialized.\n", + "In addition, planning parameters such as the planning algorithm and the number of planning attempts are defined." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_2" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Initialize the MoveGroup\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", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Query of current joint angles\n", + "Next, the current joint angles of the robot arm are queried and output in the log. The MoveGroupCommander class provides the get_current_joint_values() method.\n", + "\n", + "This harvests the current values of the joint angles and returns them as a list. The i-th entry in the list contains the angle of the i-th joint of the robot arm.\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_3", + "solution_removed_cell" + ] + }, + "outputs": [], + "source": [ + "##### YOUR CODE HERE #####\n", + "raise NotImplementedError()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Query the current end effector position\n", + "In the next step, the current pose of the end effector is queried and output in the log. The MoveGroupCommander class provides the get_current_pose() method. This method is used to determine the position and orientation of the end effector's space relative to a defined frame of reference.\n", + "\n", + "The get_current_pose() method returns a message of the type PoseStamped. This contains the position as x -, y - and z - coordinates of the end effector, the orientation describes the orientation of the end effector given as quaternion (x, y, z, w) and much more information.\n", + "\n", + ".pose is used to access the Pose attribute, which contains only the information about the position and orientation of the end effector. This attribute is of the Pose type." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_4", + "solution_removed_cell" + ] + }, + "outputs": [], + "source": [ + "##### YOUR CODE HERE #####\n", + "raise NotImplementedError()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The pose of the end effector is crucial to check the current condition of the robotic arm.\n", + "\n", + "The position is needed to ensure that the end effector is in the right place in the room.\n", + "\n", + "The orientation is essential when the end effector has to act in a certain orientation, e.g. to grasp an object correctly." + ] + }, + { + "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, + "metadata": { + "tags": [ + "task_cell_5" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Shutdown the ROS node\n", + "rospy.signal_shutdown(\"Task completed\")\n", + "roscpp_shutdown()\n", + "\n", + "##### DO NOT CHANGE #####" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_1.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_1.ipynb new file mode 100644 index 0000000..d774db9 --- /dev/null +++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_1.ipynb @@ -0,0 +1,316 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Educational Plattform Franka Emika Panda robot arm\n", + "\n", + "Author: uninh, uqwfa, ultck" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MoveIt Objects\n", + "### Task 1\n", + "\n", + "---\n", + ">\n", + "The goal of this notebook is:\n", + "- to understand how to create objects\n", + "- and how to add them to the scene\n", + ">\n", + "---\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The class PoseStamped extends the class PoseStamped, already known in Exercise_4_1, and is thus used to capture position and orientation and to associate them with a point in time, i.e. at which point in time the pose was captured.\n", + "\n", + "The PlanningSceneInterface is responsible for managing the planning scene, i.e. the environment in which the robot works. This environment contains all the obstacles and objects that need to be taken into account when planning movement." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_1" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import rospy\n", + "import sys\n", + "from geometry_msgs.msg import PoseStamped\n", + "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now ROS and MoveIt will be initialized again, as well as here the new planning scene." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_2" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Initialize the MoveIt Commander\n", + "roscpp_initialize(sys.argv)\n", + "\n", + "# Initialize the ROS Node\n", + "rospy.init_node('exercise_5_1', anonymous=True)\n", + "\n", + "# Initialize PlanningScene\n", + "scene = PlanningSceneInterface()\n", + "rospy.sleep(1)\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "This section defines the pose of an object, which is later added to the planning environment. To do this, an object of the class PoseStamped, which describes a combination of spatial position and orientation within a specific coordinate frame, is created. \n", + "\n", + "This object contains two main components:\n", + " - header: information about the coordinate frame and time stamp.\n", + " - pose: The actual position (translation) and orientation (rotation) of the object.\n", + "\n", + "Now the frame_id is set in the header of the PoseStamped-object.\n", + "\"panda_link0\" is the base frame of the robotic arm. All position and orientation information refers to this coordinate frame." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_3" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "box_pose = PoseStamped()\n", + "box_pose.header.frame_id = \"panda_link0\"\n", + "box_pose.pose.position.x = 0.4\n", + "box_pose.pose.position.y = 0.0\n", + "box_pose.pose.position.z = 0.1\n", + "box_pose.pose.orientation.w = 1.0\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "In the next section, a cube object is added to the planning environment. The PlanningSceneInterface class provides the add_box() method, which adds the object (a cube, i.e. 3-dimensional rectangular object) based on the previously defined position and orientation data of the scene.\n", + "\n", + "The add_box(name, pose, size) method must be given the following arguments :\n", + " - name (type : string): a string that describes the name of the object to be added\n", + " - pose (type: PoseStamped): the pose of the object, which consists of position and orientation\n", + " - size (type : tuple): a tuple describing the size of the box" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_4" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# adding a 5cmx5cmx5cm cube\n", + "scene.add_box(\"box_1\", box_pose, size=(0.05, 0.05, 0.05))\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Exercise 1:\n", + "\n", + " Creates a cube on the coordinates (1.0,1.0,1.0), no rotation and with the side length 10cm and adds it to the planning scene.\n", + "Give it a name: box_2.\n", + "\n", + "Proceed as follows:" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Create a new PoseStamped object and define the coordinates of the new object." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_5" + ] + }, + "outputs": [], + "source": [ + "##### WRITE YOUR CODE HERE #####\n", + "\n", + "box_pose_2 = PoseStamped()\n", + "box_pose_2.header.frame_id = \"panda_link0\"\n", + "box_pose_2.pose.position.x = 1.0\n", + "box_pose_2.pose.position.y = 1.0\n", + "box_pose_2.pose.position.z = 1.0\n", + "box_pose_2.pose.orientation.w = 1.0\n", + "\n", + "##### WRITE YOUR CODE HERE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now add the object with the specified dimensions of the scene." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_6" + ] + }, + "outputs": [], + "source": [ + "##### WRITE YOUR CODE HERE #####\n", + "\n", + "scene.add_box(\"box_2\", box_pose_2, size=(0.1, 0.1, 0.1))\n", + "\n", + "##### WRITE YOUR CODE HERE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Exercise 2:\n", + "Created a cylinder with radius 20 cm, height 1 m, which has the x coordinate 2, y coordinate 0 and z coordinate 4 and which is rotated by 90 degrees about the y axis." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_7" + ] + }, + "outputs": [], + "source": [ + "##### WRITE YOUR CODE HERE #####\n", + "\n", + "cylinder_pose = PoseStamped()\n", + "cylinder_pose.header.frame_id = \"panda_link0\"\n", + "cylinder_pose.pose.position.x = 2.0\n", + "cylinder_pose.pose.position.y = 0.0\n", + "cylinder_pose.pose.position.z = 4.0\n", + "\n", + "cylinder_pose.pose.orientation.x = 0.0\n", + "cylinder_pose.pose.orientation.y = 0.7071\n", + "cylinder_pose.pose.orientation.z = 0.0\n", + "cylinder_pose.pose.orientation.w = 0.7071\n", + "\n", + "radius = 0.2\n", + "height = 1.0\n", + "\n", + "##### WRITE YOUR CODE HERE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now add the cylinder with the defined coordinates and orientation to the scene." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_8" + ] + }, + "outputs": [], + "source": [ + "##### WRITE YOUR CODE HERE #####\n", + "\n", + "scene.add_cylinder(\"cylinder\", cylinder_pose, height=height, radius=radius)\n", + "\n", + "##### WRITE 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, + "metadata": { + "tags": [ + "task_cell_9" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Shutdown the ROS node\n", + "rospy.signal_shutdown(\"Task completed\")\n", + "roscpp_shutdown()\n", + "\n", + "##### DO NOT CHANGE #####" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_2.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_2.ipynb new file mode 100644 index 0000000..a89e4bf --- /dev/null +++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_2.ipynb @@ -0,0 +1,292 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Educational Plattform Franka Emika Panda robot arm\n", + "\n", + "Author: uninh, uqwfa, ultck" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MoveIt Objects\n", + "### Task 2\n", + "\n", + "---\n", + ">\n", + "The goal of this notebook is:\n", + "- get to know new classes for creating objects\n", + "- Stacking objects on top of each other\n", + ">\n", + "---\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "First, all necessary packages are imported.\n", + "\n", + "The SolidPrimitive class offers the ability to create simple geometric objects, such as boxes, cylinders and cones. It has the two attributes Type, which determine the type of object (e.g. BOX, CYLINDER) and Dimension, which determine the size of the object.\n", + "\n", + "The CollisionObject class is used to describe the position and orientation of the object and is used to define obstacles and objects in the scene that are taken into account in the collision check." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_1" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import sys\n", + "import rospy\n", + "from moveit_commander import roscpp_initialize, roscpp_shutdown, PlanningSceneInterface\n", + "from moveit_msgs.msg import CollisionObject\n", + "from shape_msgs.msg import SolidPrimitive\n", + "from geometry_msgs.msg import Pose\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now you initialize the ROS node, MoveIt Commander and the PlanningSceneInterface." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_2" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Initialize the MoveIt Commander\n", + "roscpp_initialize(sys.argv)\n", + "\n", + "# Initialize the ROS Node\n", + "rospy.init_node('exercise_5_2', anonymous=True)\n", + "\n", + "# Initialize the PlanningSceneInterface\n", + "planning_scene_interface = PlanningSceneInterface()\n", + "\n", + "# Wait for the planning scene interface to initialize\n", + "rospy.sleep(2)\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now create the first object, a rectangle with the following attributes :\n", + "\n", + "Size:\n", + "- width 20 cm\n", + "- Length 40 cm\n", + "- Height 40 cm\n", + "\n", + "Coordinates:\n", + "- (0.5, 0.0, 0.2)\n", + "\n", + "Directions:\n", + "- Neutral\n", + "\n", + "Important : this one has the id : rectangle_1" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_3" + ] + }, + "outputs": [], + "source": [ + "# rectangle_1\n", + "rectangle_1 = CollisionObject()\n", + "rectangle_1.id = \"rectangle_1\"\n", + "rectangle_1.header.frame_id = \"panda_link0\"\n", + "\n", + "primitive1 = SolidPrimitive()\n", + "primitive1.type = SolidPrimitive.BOX\n", + "primitive1.dimensions = [0.2, 0.4, 0.4]\n", + "\n", + "rectangle_1.primitives.append(primitive1)\n", + "\n", + "pose1 = 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", + "rectangle_1.primitive_poses.append(pose1)\n", + "rectangle_1.operation = CollisionObject.ADD\n", + "\n", + "# add rectangle_1 to the planning scene\n", + "planning_scene_interface.add_object(rectangle_1)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Next, create the second rectangle, with the same attributes as the first:\n", + "\n", + "Size:\n", + "- width 20 cm\n", + "- Length 40 cm\n", + "- Height 40 cm\n", + "\n", + "Coordinates:\n", + "- (0.5, 0.0, 0.2)\n", + "\n", + "Directions:\n", + "- Neutral\n", + "\n", + "Important : this one has the id : rectangle_2" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_4" + ] + }, + "outputs": [], + "source": [ + "# rectangle_2\n", + "rectangle_2 = CollisionObject()\n", + "rectangle_2.id = \"rectangle_2\"\n", + "rectangle_2.header.frame_id = \"panda_link0\"\n", + "\n", + "primitive2 = SolidPrimitive()\n", + "primitive2.type = SolidPrimitive.BOX\n", + "primitive2.dimensions = [0.4, 0.2, 0.4]\n", + "\n", + "rectangle_2.primitives.append(primitive2)\n", + "\n", + "pose2 = 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", + "rectangle_2.primitive_poses.append(pose2)\n", + "rectangle_2.operation = CollisionObject.ADD\n", + "\n", + "# add rectangle_2 to the planning scene\n", + "planning_scene_interface.add_object(rectangle_2)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Finally, create a rod which is placed on one of the rectangles and which has the following attributes:\n", + "\n", + "Size:\n", + "- width 2 cm\n", + "- Length 2 cm\n", + "- height 20 cm\n", + "\n", + "Coordinates:\n", + "- (0.5, 0.0, 0.5)\n", + "\n", + "Directions:\n", + "- Neutral\n", + "\n", + "Important : this one has the id : target" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_5" + ] + }, + "outputs": [], + "source": [ + "# target_object\n", + "target_object = CollisionObject()\n", + "target_object.id = \"target\"\n", + "target_object.header.frame_id = \"panda_link0\"\n", + "\n", + "primitive3 = SolidPrimitive()\n", + "primitive3.type = SolidPrimitive.BOX\n", + "primitive3.dimensions = [0.02, 0.02, 0.2]\n", + "\n", + "target_object.primitives.append(primitive3)\n", + "\n", + "pose3 = 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 = CollisionObject.ADD\n", + "\n", + "# add target_object to the planning scene\n", + "planning_scene_interface.add_object(target_object)" + ] + }, + { + "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, + "metadata": { + "tags": [ + "task_cell_6" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Shutdown the ROS node\n", + "rospy.signal_shutdown(\"Task completed\")\n", + "roscpp_shutdown()\n", + "\n", + "##### DO NOT CHANGE #####" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_3.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_3.ipynb new file mode 100644 index 0000000..a6c5c46 --- /dev/null +++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_objects/move_it_objects_3.ipynb @@ -0,0 +1,172 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Educational Plattform Panda Robot\n", + "\n", + "Author: uninh, uqwfa, ultck" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MoveIt Objects\n", + "### Task 3\n", + "\n", + "---\n", + "> \n", + "The goal of this notebook is:\n", + "- to understand how to remove objects from a scene\n", + "- to check which objects are currently in the scene\n", + "> \n", + "\n", + "---" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We import the same packages we did in the previous task." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_1" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import rospy\n", + "import sys\n", + "from geometry_msgs.msg import PoseStamped\n", + "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now ROS, MoveIt and the PlanningScene will be initialized." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_2" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Initialize the MoveIt Commander\n", + "roscpp_initialize(sys.argv)\n", + "\n", + "# Initialize the ROS Node\n", + "rospy.init_node('exercise_5_1', anonymous=True)\n", + "\n", + "# Initialize PlanningScene\n", + "scene = PlanningSceneInterface()\n", + "rospy.sleep(1)\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now remove the two objects added in the previous task of the scene. This is possible using the method provided by the PlanningSceneInterface class, remove_world_object(name), where name is the sting name of the object to be removed.\n", + "\n", + "You can also remove all objects in the scene at once by calling remove_world_object() without parameter." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_3", + "solution_removed_cell" + ] + }, + "outputs": [], + "source": [ + "##### YOUR CODE HERE #####\n", + "raise NotImplementedError()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now check that all objects have been removed from the scene. This is where the get_known_object_names() method, which is also provided by the PlanningSceneInterface class, comes in handy. This method returns a list of strings, with each string representing the name of a known object in the scene." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_4" + ] + }, + "outputs": [], + "source": [ + "##### WRITE 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 #####" + ] + }, + { + "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, + "metadata": { + "tags": [ + "task_cell_5" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Shutdown the ROS node\n", + "rospy.signal_shutdown(\"Task completed\")\n", + "roscpp_shutdown()\n", + "\n", + "##### DO NOT CHANGE #####" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} \ No newline at end of file -- GitLab