diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb index 4ad40f7e1b29861972bccc73d6d52c427c797822..22761841b823cfc0189420b1f09e205a4adba1f4 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb @@ -32,7 +32,7 @@ "##### DO NOT CHANGE #####\n", "\n", "import rospy\n", - "from controller_manager_msgs.srv import LoadController, SwitchController\n", + "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController\n", "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n", "\n", "##### DO NOT CHANGE #####" @@ -64,22 +64,51 @@ "source": [ "##### DO NOT CHANGE #####\n", "\n", + "import rospy\n", + "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController\n", + "\n", + "controller_name = 'position_joint_trajectory_controller'\n", + "conflicting_controller = 'effort_joint_trajectory_controller'\n", + "\n", + "# Funktion zum Entladen eines Controllers\n", + "def unload_controller(controller_name):\n", + " rospy.wait_for_service('/controller_manager/switch_controller')\n", + " try:\n", + " switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", + " req = SwitchControllerRequest()\n", + " req.stop_controllers = [controller_name]\n", + " req.strictness = SwitchControllerRequest.BEST_EFFORT\n", + " response = switch_controller(req)\n", + " assert response.ok, \"Controller konnte nicht entladen werden.\"\n", + " except rospy.ServiceException as e:\n", + " rospy.logerr(\"Service call failed: %s\" % e)\n", + " rospy.wait_for_service('/controller_manager/unload_controller')\n", + " try:\n", + " unload_srv = rospy.ServiceProxy('/controller_manager/unload_controller', UnloadController)\n", + " unload_resp = unload_srv(controller_name)\n", + " assert unload_resp.ok, \"Controller konnte nicht entladen werden.\"\n", + " except rospy.ServiceException as e:\n", + " rospy.logerr(\"Service call failed: %s\" % e)\n", + "\n", + "# Entladen des alten Controllers\n", + "unload_controller(conflicting_controller)\n", + "\n", "# Service für das Laden des Controllers\n", "rospy.wait_for_service('/controller_manager/load_controller')\n", "load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n", - "response = load_service(\"position_joint_trajectory_controller\")\n", + "response = load_service(controller_name)\n", "assert response.ok, \"Controller konnte nicht geladen werden.\"\n", "\n", "# Service für das Aktivieren des Controllers\n", "rospy.wait_for_service('/controller_manager/switch_controller')\n", "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", - "response = switch_service(start_controllers=['position_joint_trajectory_controller'], \n", - " stop_controllers=[], strictness=1)\n", + "switch_req = SwitchControllerRequest()\n", + "switch_req.start_controllers = [controller_name]\n", + "switch_req.strictness = SwitchControllerRequest.BEST_EFFORT\n", + "response = switch_service(switch_req)\n", "assert response.ok, \"Controller konnte nicht gestartet werden.\"\n", "\n", - "print(\"Position Controller erfolgreich gestartet.\")\n", - "\n", - "##### DO NOT CHANGE #####\n" + "##### DO NOT CHANGE #####" ] }, { @@ -126,12 +155,12 @@ "\n", "# Erstelle die Nachricht\n", "traj_msg = JointTrajectory()\n", - "traj_msg.joint_names = [...] # TODO: Füge die Gelenknamen des Roboters hier ein\n", + "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n", "\n", "# Definiere die Zielpositionen\n", "point = JointTrajectoryPoint()\n", - "point.positions = [...] # TODO: Füge Zielpositionen (in Radiant) für jedes Gelenk hinzu\n", - "point.time_from_start = rospy.Duration(...) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll\n", + "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0] # TODO: Füge Zielpositionen (in Radiant) für jedes Gelenk hinzu\n", + "point.time_from_start = rospy.Duration(2.0) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll\n", "\n", "# Füge den Punkt zur Trajektorie hinzu\n", "traj_msg.points.append(point)\n", @@ -176,17 +205,17 @@ "\n", "# Nachricht erstellen\n", "traj_msg = JointTrajectory()\n", - "traj_msg.joint_names = ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6']\n", + "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n", "\n", "# Erste Zielposition definieren\n", "point1 = JointTrajectoryPoint()\n", - "point1.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5]\n", + "point1.positions = [0.6, -0.6, 0.2, 0.2, 0.5, -0.5, 0.2]\n", "point1.time_from_start = rospy.Duration(2.0)\n", "traj_msg.points.append(point1)\n", "\n", "# Zweite Zielposition definieren\n", "point2 = JointTrajectoryPoint()\n", - "point2.positions = [1.0, 0.0, -0.5, 0.0, -0.5, 1.0]\n", + "point2.positions = [0.7, -0.2, -0.5, -0.2, -0.5, 0.7, -0.2]\n", "point2.time_from_start = rospy.Duration(5.0)\n", "traj_msg.points.append(point2)\n", "\n", diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb index eb4b28c02cbb28279359a136eca7b8a960428c2f..aed79f37a9c5176f84d1cbfe2c29ff90d30b595e 100644 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb +++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb @@ -18,19 +18,21 @@ "\n", "---\n", ">\n", - "Ziel dieses Notebooks ist :\n", - "- den Roboterarm durch eine Serie von vorgegebenen Positionen (Wegpunkte) im kartesischen Raum zu bewegen\n", - "- wie man Bewegungen planen kann, die entlang einer komplexen Trajektorie ablaufen \n", - "- wie mehrere Positionen definiert, in eine Trajektorie umgewandelt und schließlich ausgeführt werden können\n", + "The goal of this notebook is :\n", + "- to move the robotic arm through a series of predetermined positions (waypoints) in Cartesian space\n", + "- how to plan movements that run along a complex trajectory \n", + "- how multiple positions can be defined, converted into a trajectory and finally executed\n", ">\n", - "---\n" + "---" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ - "TODO : Beschreiben der Funktionalität der Pakete, wenn man nicht in vorheriger Aufgabe schon gemacht hat" + "First, all the necessary packages and classes are imported. You already know these from the move_it_basics and move_it_objects tasks.\n", + "\n", + "Then, as usual, we initialize the MoveIt Commander, create a ROS node and initialize the Move Group." ] }, { @@ -46,30 +48,11 @@ "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n", "from geometry_msgs.msg import Pose\n", "\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "TODO : Initialisierung beschreiben was man macht" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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_6_1', anonymous=True)\n", + "rospy.init_node('move_it_intermediate', anonymous=True)\n", "\n", "# Initialize the MoveGroup\n", "group = MoveGroupCommander('panda_arm')\n", @@ -81,7 +64,8 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Mit group.get_current_pose() fragt man in MoveIt die aktuelle Pose des Endeffektors ab. Die Methode gibt ein PoseStamped-Objekt zurück, dessen Eigenschaft pose die eigentliche Geometrie (Position und Orientierung) enthält" + "With group.get_current_pose() you query the current pose of the end effector in MoveIt. The method returns a PoseStamped-object, whose pose property contains the actual geometry (position and orientation). \n", + "So your task is to first create a variable current_pose and then store the current pose of the end effector in it." ] }, { @@ -102,7 +86,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Füge alle Wegpunkte, die der Roboterarm ablaufen soll der hier definierten liste waypoints hinzu." + "Here a list of waypoints is initialized, in which all waypoints that the robot arm should run must be added later." ] }, { @@ -113,7 +97,7 @@ "source": [ "##### DO NOT CHANGE #####\n", "\n", - "# Define the waypoints\n", + "# Define the waypoints the robot should move to\n", "waypoints = []\n", "\n", "##### DO NOT CHANGE #####" @@ -123,13 +107,13 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Nun soll der erste Wegpunkt definiert werden. Erstelle also ein neues Objekt von der Klasse pose.\n", + "Now you want to define the first waypoint. So create a new object from the class pose.\n", "\n", - "Für den ersten Wegpunkt soll sich der Roboterarm um 10 cm (0.1) entlang der X - Achse bewegen, wobei die y - Koordinate und z - Koordinate, sowie die Orientierung unverändert bleiben soll.\n", + "For the first waypoint the robot arm should move 10 cm (0.1) along the X axis, whereby the y coordinate and z coordinate as well as the orientation should remain unchanged.\n", "\n", - "Füge diesen Wegpunt am Ende der liste waypoints hinzu.\n", + "Add this waypunt at the end of the waypoints list.\n", "\n", - "Tipp : setze diese mithilfe der current pose um" + "Tip: Do this with the current pose" ] }, { @@ -154,12 +138,12 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Erzeuge als nächstes einen zweiten Wegpunkt , ebenfalls vom Typ Pose.\n", + "Next, create a second waypoint, also of the pose type.\n", "\n", - "Halte hier nun die X- und Z-Positionen aus dem ersten Wegpunkt bei und verschiebe die Y-Position um 0,2 (20 cm).\n", - "Wieder gilt, dass die Orientierung aus der current_pose übernommen werden soll.\n", + "Now hold the X and Z positions from the first waypoint and shift the Y position by 0.2 (20 cm).\n", + "Again, the orientation should be taken from the current_pose.\n", "\n", - "Füge zuletzt den neuen Wegpunkt zur waypoints-Liste hinzu." + "Finally, add the new waypoint to the waypoints list." ] }, { @@ -184,12 +168,12 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Der letzte Wegpunkt soll auch wieder vom Typ Pose sein.\n", + "The last waypoint should also be of the type Pose.\n", "\n", - "Halte hier die X- und Y-Positionen aus dem zweiten Wegpunkt bei und verschiebe die Z-Position um 0,4 (40 cm) nach oben.\n", - "Übernimm die Orientierung aus der current_pose.\n", + "Hold the X and Y positions from the second waypoint and move the Z position 0.3 (30 cm) up.\n", + "Take the orientation from the current_pose.\n", "\n", - "Füge den neuen Wegpunkt zur waypoints-Liste hinzu." + "Add the new waypoint to the waypoints list." ] }, { @@ -203,7 +187,7 @@ "waypoint_3 = Pose()\n", "waypoint_3.position.x = waypoint_2.position.x\n", "waypoint_3.position.y = waypoint_2.position.y\n", - "waypoint_3.position.z = waypoint_2.position.z + 0.4\n", + "waypoint_3.position.z = waypoint_2.position.z + 0.3\n", "waypoint_3.orientation = current_pose.orientation\n", "waypoints.append(waypoint_3)\n", "\n", @@ -214,13 +198,13 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Nun werden Parameter definiert, welche die folgende Bedeutung haben :\n", + "Now we define parameters that have the following meaning:\n", "\n", - "fraction = 0.0, setzt den initialen Wert des berechneten Pfadanteils auf 0,\n", + "fraction = 0.0, sets the initial value of the calculated path portion to 0,\n", "\n", - "max_attempts = 100, legt die maximale Anzahl der Versuche fest, um den Pfad zu berechnen,\n", + "max_attempts = 100, sets the maximum number of attempts to calculate the path,\n", "\n", - "attempts = 0, zählt die Anzahl der Versuche." + "attempts = 0, counts the number of attempts." ] }, { @@ -243,11 +227,11 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Erstelle eine Schleife, die läuft, solange der berechnete Pfadanteil (fraction) kleiner als 1.0 ist und die Anzahl der Versuche (attempts) kleiner als max_attempts ist.\n", + "Create a loop that runs as long as the calculated fraction is less than 1.0 and the number of attempts is less than max_attempts.\n", "\n", - "Innerhalb der Schleife, berechne den kartesischen Pfad basierend auf den angegebenen Wegpunkten (waypoints). Verwende 0.01 als Schrittabstand des Endeffektors und 0.0 als Sprungschwellenwert. Die Methode gibt einen Bewegungsplan (plan) und den berechneten Pfadanteil (fraction) zurück.\n", + "Within the loop, calculate the Cartesian path based on the specified waypoints. Use 0.01 as the step distance of the end effector and 0.0 as the jump threshold. The method returns a plan of motion and the calculated path fraction.\n", "\n", - "Erhöhe am Ende innerhalb der Schleife die Anzahl der Versuche um 1." + "Don't forget to increase the number of attempts by 1 at the end of the loop." ] }, { @@ -269,7 +253,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Mithilfe der Methode execute wird nun der erstellte plan ausgeführt." + "The executed method now executes the created plan." ] }, { @@ -281,9 +265,7 @@ "##### DO NOT CHANGE #####\n", "\n", "if fraction == 1.0:\n", - " rospy.loginfo(\"Successfully computed the Cartesian path. Executing...\")\n", " group.execute(plan, wait=True)\n", - " rospy.loginfo(\"Execution completed.\")\n", "else:\n", " rospy.logwarn(f\"Failed to compute a complete path after {attempts} attempts.\")\n", "\n", @@ -307,7 +289,6 @@ "##### DO NOT CHANGE #####\n", "\n", "# Shutdown the ROS node\n", - "rospy.signal_shutdown(\"Task completed\")\n", "roscpp_shutdown()\n", "\n", "##### DO NOT CHANGE #####" diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..04e812f621bccae9a219a562e1b708c38ebb0906 --- /dev/null +++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller.ipynb @@ -0,0 +1,294 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Learn Environment Panda Robot\n", + "Author: NAME" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Controller_Task\n", + "### Position_Controller\n", + "\n", + "> In this task, you will learn ...\n", + ">\n", + "> - wie du mit einem Position Controller arbeitest, um die Gelenke eines Roboters auf spezifische Positionen zu bewegen.\n", + "> - wie man den Position Controller startet\n", + "> - wie man eine Nachricht für den Position Controller erstellt\n", + "> - wie man die Zielposition sendt und die Bewegung überprüft" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_1" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import rospy\n", + "from controller_manager_msgs.srv import LoadController, SwitchController\n", + "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Lade den Controller:\n", + "\n", + "ROS verwendet den Service /controller_manager/load_controller, um Controller zu laden.\n", + "Du musst den Namen des Controllers angeben, den du laden möchtest, in diesem Fall position_joint_trajectory_controller.\n", + "Aktiviere den Controller:\n", + "\n", + "Nachdem der Controller geladen ist, musst du ihn starten. Dies geschieht mit dem Service /controller_manager/switch_controller.\n", + "Du kannst mehrere Controller gleichzeitig starten und stoppen, indem du deren Namen in den Service-Request übergibst.\n", + "Verwende die folgende Vorlage:\n", + "\n", + "Nutze den Service load_controller, um den gewünschten Controller zu laden.\n", + "Starte den Service switch_controller, um den Position Controller zu aktivieren." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_2" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "import rospy\n", + "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController\n", + "\n", + "controller_name = 'position_joint_trajectory_controller'\n", + "conflicting_controller = 'effort_joint_trajectory_controller'\n", + "\n", + "# Funktion zum Entladen eines Controllers\n", + "def unload_controller(controller_name):\n", + " rospy.wait_for_service('/controller_manager/switch_controller')\n", + " try:\n", + " switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", + " req = SwitchControllerRequest()\n", + " req.stop_controllers = [controller_name]\n", + " req.strictness = SwitchControllerRequest.BEST_EFFORT\n", + " response = switch_controller(req)\n", + " assert response.ok, \"Controller konnte nicht entladen werden.\"\n", + " except rospy.ServiceException as e:\n", + " rospy.logerr(\"Service call failed: %s\" % e)\n", + " # Nach dem Stoppen auch wirklich entladen:\n", + " rospy.wait_for_service('/controller_manager/unload_controller')\n", + " try:\n", + " unload_srv = rospy.ServiceProxy('/controller_manager/unload_controller', UnloadController)\n", + " unload_resp = unload_srv(controller_name)\n", + " assert unload_resp.ok, \"Controller konnte nicht entladen werden.\"\n", + " except rospy.ServiceException as e:\n", + " rospy.logerr(\"Service call failed: %s\" % e)\n", + "\n", + "# Entladen des konfliktierenden Controllers\n", + "unload_controller(conflicting_controller)\n", + "\n", + "# Service für das Laden des Controllers\n", + "rospy.wait_for_service('/controller_manager/load_controller')\n", + "rospy.loginfo('Versuche, /controller_manager/load_controller aufzurufen...')\n", + "load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n", + "response = load_service(controller_name)\n", + "rospy.loginfo('LoadController-Antwort: {}'.format(response))\n", + "assert response.ok, \"Controller konnte nicht geladen werden.\"\n", + "\n", + "# Service für das Aktivieren des Controllers\n", + "rospy.wait_for_service('/controller_manager/switch_controller')\n", + "rospy.loginfo('Versuche, /controller_manager/switch_controller aufzurufen...')\n", + "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n", + "switch_req = SwitchControllerRequest()\n", + "switch_req.start_controllers = [controller_name]\n", + "switch_req.strictness = SwitchControllerRequest.BEST_EFFORT\n", + "response = switch_service(switch_req)\n", + "rospy.loginfo('SwitchController-Antwort: {}'.format(response))\n", + "assert response.ok, \"Controller konnte nicht gestartet werden.\"\n", + "\n", + "print(\"Position Controller erfolgreich gestartet.\")\n", + "\n", + "##### DO NOT CHANGE #####\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Nachrichtentyp:\n", + "\n", + "Der Position Controller empfängt Nachrichten vom Typ trajectory_msgs/JointTrajectory.\n", + "Diese Nachricht enthält:\n", + "joint_names: Eine Liste der Gelenke, die gesteuert werden sollen.\n", + "points: Eine Liste von Positionen, die die Gelenke ansteuern sollen.\n", + "Erstelle die Nachricht:\n", + "\n", + "Beginne mit einer JointTrajectory-Nachricht.\n", + "Definiere die Gelenke, die du bewegen möchtest, indem du die Namen in der Liste joint_names einträgst.\n", + "Füge Zielpositionen hinzu:\n", + "\n", + "Erstelle ein JointTrajectoryPoint, um die Zielpositionen für jedes Gelenk zu definieren.\n", + "Ergänze die Felder:\n", + "positions: Die Zielpositionen in Radiant (z. B. [0.5, -0.5, 0.0]).\n", + "time_from_start: Die Dauer, die der Roboter benötigt, um die Positionen zu erreichen.\n", + "Sende die Nachricht:\n", + "\n", + "Veröffentliche die Nachricht auf dem Topic /position_joint_trajectory_controller/command." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_3" + ] + }, + "outputs": [], + "source": [ + "##### DO NOT CHANGE #####\n", + "\n", + "# Initialisiere ROS\n", + "rospy.init_node('position_control', anonymous=True)\n", + "\n", + "# Publisher für das Command-Topic\n", + "pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)\n", + "\n", + "# Warte, bis der Publisher bereit ist\n", + "rospy.sleep(1)\n", + "\n", + "# Erstelle die Nachricht\n", + "traj_msg = JointTrajectory()\n", + "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n", + "\n", + "# Definiere die Zielpositionen\n", + "point = JointTrajectoryPoint()\n", + "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0] # TODO: Füge Zielpositionen (in Radiant) für jedes Gelenk hinzu\n", + "point.time_from_start = rospy.Duration(2.0) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll\n", + "\n", + "# Füge den Punkt zur Trajektorie hinzu\n", + "traj_msg.points.append(point)\n", + "\n", + "# Sende die Nachricht\n", + "pub.publish(traj_msg)\n", + "print(\"Zielposition wurde gesendet.\")\n", + "\n", + "##### DO NOT CHANGE #####" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "In dieser Erweiterung definieren Sie zwei Zielpositionen.\n", + "Die erste Zielposition wird erreicht, bevor der Roboter zur zweiten Zielposition übergeht.\n", + "Was du tun musst:\n", + "\n", + "Füge eine zweite Zielposition zu traj_msg.points hinzu.\n", + "Die zweite Zielposition sollte eine andere Pose ansteuern, um eine sichtbare Bewegung zu demonstrieren.\n", + "Planung der Bewegung:\n", + "\n", + "Verwenden Sie die Zeitsteuerung time_from_start, um sicherzustellen, dass der Roboter genug Zeit hat, die erste Position zu erreichen, bevor er zur nächsten übergeht.\n", + "Die Zeitangaben müssen aufeinander aufbauen:\n", + "Die erste Zielposition benötigt z. B. 2 Sekunden (time_from_start = 2.0).\n", + "Die zweite Zielposition wird nach weiteren 3 Sekunden erreicht (time_from_start = 5.0).\n", + "Schritte:\n", + "\n", + "Erstelle eine erste Zielposition: Definiere die Gelenkwinkel und die Dauer.\n", + "Erstelle eine zweite Zielposition: Erhöhe die Zeit und ändere die Gelenkwinkel.\n", + "Sende beide Punkte: Füge die Punkte zu traj_msg.points hinzu und sende die Nachricht." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_4", + "solution_removed_cell" + ] + }, + "outputs": [], + "source": [ + "##### YOUR CODE HERE #####\n", + "raise NotImplementedError()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "solution_cell" + ] + }, + "outputs": [], + "source": [ + "##############################################################\n#### THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE. ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n#### USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE. ####\n##############################################################\n\n", + "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n", + "\n", + "# Nachricht erstellen\n", + "traj_msg = JointTrajectory()\n", + "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n", + "\n", + "# Erste Zielposition definieren\n", + "point1 = JointTrajectoryPoint()\n", + "point1.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]\n", + "point1.time_from_start = rospy.Duration(2.0)\n", + "traj_msg.points.append(point1)\n", + "\n", + "# Zweite Zielposition definieren\n", + "point2 = JointTrajectoryPoint()\n", + "point2.positions = [1.0, 0.0, -0.5, 0.0, -0.5, 1.0, 0.0]\n", + "point2.time_from_start = rospy.Duration(5.0)\n", + "traj_msg.points.append(point2)\n", + "\n", + "# Nachricht senden\n", + "pub.publish(traj_msg)\n", + "print(\"Zwei Zielpositionen wurden gesendet.\")\n", + "\n", + "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "task_cell_5" + ] + }, + "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 +} \ No newline at end of file