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 80e4c3adda686f8c6478c34115e2f9c78c2ebcd6..0000000000000000000000000000000000000000 --- 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 dd51aa6ed15734a5e6e0241e6659f925146df2d4..0000000000000000000000000000000000000000 --- 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 a953b24dd8056d8b476cf38d81c8087525c31d88..0000000000000000000000000000000000000000 --- 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 e6e784f811d5d4ec4766c3ac9e8c20aea368d884..0000000000000000000000000000000000000000 --- 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_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 d9ef4825c151e68d24544e3a42333a72c97be05e..0000000000000000000000000000000000000000 --- 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/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py index 34b858e38fe27ece67fc324c53acd4f5d260d8ef..e3708a23bdba9ecf57bfb5e6e8997b362d6b688c 100644 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py +++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py @@ -22,7 +22,8 @@ for i, (current, expected) in enumerate(zip(current_joint_values, expected_value if abs(current - expected) > error_margin: roscpp_shutdown() - print("false, Joint {} is not in the correct position".format(i)) + print('Joint {} is not in the correct position'.format(i)) + print('false') sys.exit(0) roscpp_shutdown() 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/move_it/move_it_basics/move_it_basics_2_eval.py similarity index 64% rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_2_eval.py rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_2_eval.py index bc5e0d9bc962405e43b258aeee47cc5ffc4c124f..2aac46c7ba647c91439cbd532c4c8d9a76bf0b74 100644 --- 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/move_it/move_it_basics/move_it_basics_2_eval.py @@ -1,20 +1,15 @@ 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) +rospy.init_node('move_it_basics_2_eval', 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, @@ -26,12 +21,26 @@ current_values = [ current_pose.orientation.w ] +value_names = [ + "position.x", + "position.y", + "position.z", + "orientation.x", + "orientation.y", + "orientation.z", + "orientation.w" +] + +expected_pose = [0.5, 0.0, 0.2, 0.5, 0.5, 0.5, 0.5] +error_margin = 0.01 + 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)) + print("Pose component \'{}\' is not in the correct position".format(value_names[i])) + print("false") sys.exit(0) roscpp_shutdown() diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py index 0a873779919936d1c60a6f919316afd7d9ee87cb..cd936d2f2d0236295771e97212ab680765b86291 100644 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py +++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py @@ -68,7 +68,7 @@ elif not node_exists: print('false') else: - print('Messages not received') + print('No messages received on the /chatter topic') print('false') diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py index 325bffa4544f25145e1ed4f91233a055593e0c71..9d617367ddbbd31b811c2e2d2217a80f8e6f7117 100644 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py +++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py @@ -32,6 +32,9 @@ def checkSubscribtion(): subs = [x[2] for x in subs if x[0] == topic] + if len(subs) == 0: + return False + for sub in subs[0]: if re.match(pattern, sub): return True @@ -67,9 +70,11 @@ if node_exist and sub_exist: print('true') elif not node_exist: - print('false: node does not exist') + print('node not found') + print('false') else: - print('false: subscriber does not exist') + print('subscriber does not exist') + print('false') rospy.signal_shutdown('evaluation done') \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py index d79bc87b773df69ca4b2c2e85b97897db469a1f0..188e9b16427e9dffe9faeb6292e3a5cb73c3dfa0 100644 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py +++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py @@ -18,7 +18,8 @@ for i, (current, expected) in enumerate(zip(current_joint_values, expected_value if abs(current - expected) > error_margin: roscpp_shutdown() - print("false: Joint {} is not in the correct position".format(i+1)) + print("Joint {} is not in the correct position".format(i+1)) + print('false') sys.exit(0) roscpp_shutdown() diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py index 93ca1d4c4f77d7de8738e1da5bee07850e764c57..acdaac6ba533e10bd3ca4e4344d00f37a6b33b11 100644 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py +++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py @@ -21,7 +21,6 @@ class Eval(): self.current_joint_values = msg def joint_trajectory_callback(self, msg): - rospy.loginfo('got msg') self.received_msg = True def evaluate_position(self, target_position): @@ -56,7 +55,6 @@ for target_position in target_positions_sequence: if x.evaluate_position(target_position): - rospy.loginfo('position sucessful') sucessful_positions += 1 break @@ -72,7 +70,9 @@ if sucessful_positions == 3: print('true') elif not x.received_msg: - print('false: no message received on the topic') + print('no message received on the topic') + print('false') else: - print('false: position {} not reached'.format(sucessful_positions + 1)) \ No newline at end of file + print('position {} not reached'.format(sucessful_positions + 1)) + print('false') \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/reset_robot.py b/catkin_ws/src/learn_environment/task_pool/reset_robot.py index 0021c1173fbf7fc9554209a43db11f6b966bfa3d..6016e20d6188cfd45d8f8748e03d994594907588 100644 --- a/catkin_ws/src/learn_environment/task_pool/reset_robot.py +++ b/catkin_ws/src/learn_environment/task_pool/reset_robot.py @@ -5,8 +5,16 @@ import sys from moveit_commander import MoveGroupCommander, PlanningSceneInterface, roscpp_initialize, roscpp_shutdown -def reset_robot(): - group = MoveGroupCommander("panda_arm") +def robot_already_in_default_position(group, robot_default_position): + current_joint_values = group.get_current_joint_values() + + for i in range(7): + if abs(current_joint_values[i] - robot_default_position[i]) > 0.01: + return False + + return True + +def reset_robot(group): group.set_max_velocity_scaling_factor(1.0) group.set_max_acceleration_scaling_factor(1.0) @@ -24,9 +32,7 @@ def reset_robot(): group.go(wait=True) -def remove_objects(): - scene = PlanningSceneInterface(synchronous=True) - rospy.sleep(2) +def remove_objects(scene): objects = scene.get_known_object_names() for object_name in objects: @@ -37,10 +43,19 @@ def remove_objects(): rospy.init_node('reset', anonymous=True) roscpp_initialize(sys.argv) +group = MoveGroupCommander("panda_arm") + +robot_default_position = [0.0, -math.pi / 4, 0.0, -math.pi * 3 / 4, 0.0, math.pi / 2, math.pi / 4] + +if not robot_already_in_default_position(group, robot_default_position): + reset_robot(group) + +scene = PlanningSceneInterface(synchronous=True) -reset_robot() -remove_objects() +if len(scene.get_known_object_names()) > 0: + remove_objects(scene) roscpp_shutdown() +rospy.signal_shutdown("Task completed.") print("Successfully reset the robot and removed all objects.") \ 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 6bf0ed8dacb1ebb8d8bd97c674822295fd3ce036..0000000000000000000000000000000000000000 --- 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 560e4481471b2d5c9fd70dc4c5a1810819f233fb..0000000000000000000000000000000000000000 --- 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 b77aae01cf6b91a2eb35d24e3690d844cb7c9f39..0000000000000000000000000000000000000000 --- 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 078a3d55f6a831cd1f889b9c7c18bbed3b92274a..0000000000000000000000000000000000000000 --- 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_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 3aab6e8b040cb3127a77639b9bbc30a2c67b655d..0000000000000000000000000000000000000000 --- 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/solution_scripts/beginner/exercise_2/exercise_2_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb similarity index 55% rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_2.ipynb rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb index 9b3ccdceeccf1a572a754c7143db94a6412bf811..c40ea1e73862eac50deb222ba9e6ea403de367ec 100644 --- 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/move_it/move_it_basics/move_it_basics_2.ipynb @@ -12,12 +12,15 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "### Exercise_2_2\n", + "## MoveIt Basics\n", + "### Task 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", + "> - ... how to move the robot to a specific cartesian position.\n", + "> - ... how to determine the joint values that represent a Cartesian position (alternative).\n", + "\n", "---" ] }, @@ -25,7 +28,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "For this we need the `MoveGroupCommander`." + "As always, we need to start by implementing the required modules." ] }, { @@ -49,7 +52,13 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Initialize the ``MoveIt Commander``, launch a ``ROS node``, and create a ``MoveGroupCommander`` instance." + "Next, we need to initialize ``roscpp``, set up a ``ROS node``, and implement a ``MoveGroupCommander`` instance.\n", + "\n", + "ToDo:\n", + "\n", + "- initialize ``roscpp`` with ``sys.argv`` as an argument\n", + "- initialize a ``ROS node``\n", + "- assign a ``MoveGroupCommander`` instace to ``group``" ] }, { @@ -58,10 +67,12 @@ "metadata": {}, "outputs": [], "source": [ + "group = None\n", + "\n", "##### YOUR CODE HERE #####\n", "\n", "roscpp_initialize(sys.argv)\n", - "rospy.init_node('exercise_2_2', anonymous=True)\n", + "rospy.init_node('commander', anonymous=True)\n", "group = MoveGroupCommander(\"panda_arm\")\n", "\n", "##### YOUR CODE HERE #####" @@ -80,12 +91,12 @@ "metadata": {}, "outputs": [], "source": [ - "##### WRITE YOUR CODE HERE #####\n", + "##### 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 #####" + "##### YOUR CODE HERE #####" ] }, { @@ -94,16 +105,19 @@ "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", + "- ``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", + "Since the orientation values use a ``quaternion`` representation, they must 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." + "ToDo:\n", + "\n", + "- set the ``position.y`` to 0.0 and ``position.z`` to 0.2\n", + "- set the ``orientation -y, -z, -w`` to 0.5" ] }, { @@ -112,29 +126,29 @@ "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", + "target_pose.position.x = 0.5\n", + "target_pose.orientation.x = 0.5\n", "\n", + "##### YOUR CODE HERE #####\n", "\n", - "target_pose.position.y = -0.2\n", - "target_pose.position.z = 0.8\n", + "target_pose.position.y = 0.0\n", + "target_pose.position.z = 0.2\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 #####" + "target_pose.orientation.y = 0.5\n", + "target_pose.orientation.z = 0.5\n", + "target_pose.orientation.w = 0.5\n", + "\n", + "##### 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. " + "Next, we aim to retrieve the joint values required to move the ``gripper`` to specific Cartesian positions. To achieve this, we use the ``plan()`` method of the ``MoveGroupCommander``. This method generates a motion plan to the defined goal state, essentially providing a sequence of joint values the robot must follow to reach the target joint state. Our focus is on extracting the last joint values in the sequence, representing the final goal corresponding to the target Cartesian position. Check the terminal to verify if the final goal joint values remain consistent for the same Cartesian position (look for the 'Output of Robot Script:' lines)." ] }, { @@ -145,11 +159,13 @@ "source": [ "##### DO NOT CHANGE #####\n", "\n", - "plan = group.plan(target_pose)\n", + "for i in range(5):\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", + " point_list = plan[1].joint_trajectory.points\n", + " last_point = point_list[-1].positions\n", + "\n", + " rospy.loginfo(last_point)\n", "\n", "##### DO NOT CHANGE #####" ] @@ -158,7 +174,9 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Next we want to execute the movement with the ``joint_values``." + "If done correctly, you might notice that the joint values are sometimes slightly different, and sometimes the +/ - signs are inverted. This happens because there isn’t just one correct solution. Different joint configurations can result in the same Cartesian position.\n", + "\n", + "Finally, we set the target Cartesian pose using the ``set_pose_target()`` method of the ``MoveGroupCommander`` and execute the motion with the ``go()`` method." ] }, { @@ -167,19 +185,19 @@ "metadata": {}, "outputs": [], "source": [ - "##### YOUR CODE HERE #####\n", + "##### DO NOT CHANGE #####\n", "\n", - "group.set_joint_value_target(joint_values)\n", + "group.set_pose_target(target_pose)\n", "group.go(wait=True)\n", "\n", - "##### YOUR CODE HERE #####" + "##### DO NOT CHANGE #####" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ - "And, as always, we shut down the initialized modules." + "At the end, we need to shut everything down." ] }, { 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 d71b061a73510201942a0edd29b5e08c1f479c05..c6b804c9210368adf31b89cfcb58225f8e3b8f4f 100644 --- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json +++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json @@ -8,7 +8,7 @@ "subtasks": [ { "title": "Task 1", - "description": "TODO: Add Subtask Description Subtask 1.", + "description": "Explains the ROS system and implement a simple publisher.", "solution_file": "/ros_basics_1.ipynb", "evaluation_file": "/ros_basics_1_eval.py", "parallelized_evaluation_required": true, @@ -16,16 +16,18 @@ }, { "title": "Task 2", - "description": "TODO: Add Subtask Description Subtask 1.", + "description": "Implement a simple subscriber.", "solution_file": "/ros_basics_2.ipynb", "evaluation_file": "/ros_basics_2_eval.py", - "parallelized_evaluation_required": true + "parallelized_evaluation_required": true, + "reset_robot_before_executing": false }, { "title": "Task 3", - "description": "TODO: Add Subtask Description Subtask 1.", + "description": "Learn useful ROS commands and ROS topics", "solution_file": "/ros_basics_3.ipynb", - "evaluation_file": "/ros_basics_3_eval.py" + "evaluation_file": "/ros_basics_3_eval.py", + "reset_robot_before_executing": false } ] }, @@ -37,15 +39,16 @@ "subtasks": [ { "title": "Task 1", - "description": "TODO: Add Subtask Description Subtask 1.", + "description": "Implement your first simple movement.", "solution_file": "/ros_intermediate_1.ipynb", "evaluation_file": "/ros_intermediate_1_eval.py" }, { "title": "Task 2", - "description": "TODO: Add Subtask Description Subtask 2.", + "description": "Implement a more complex sequence of movements.", "solution_file": "/ros_intermediate_2.ipynb", - "evaluation_file": "/ros_intermediate_2_eval.py" + "evaluation_file": "/ros_intermediate_2_eval.py", + "parallelized_evaluation_required": true } ] }, @@ -57,9 +60,15 @@ "subtasks": [ { "title": "Task 1", - "description": "TODO: Add Subtask Description Subtask 1.", + "description": "Implement a simple movement with MoveIt.", "solution_file": "/move_it_basics_1.ipynb", "evaluation_file": "/move_it_basics_1_eval.py" + }, + { + "title": "Task 2", + "description": "Implement a simple movement with MoveIt.", + "solution_file": "/move_it_basics_2.ipynb", + "evaluation_file": "/move_it_basics_2_eval.py" } ] }, @@ -77,70 +86,6 @@ } ] }, - { - "title": "Task 1 (TODO: Rename)", - "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)", - "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)", - "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)", "topic": "Topic 3",