Skip to content
Snippets Groups Projects
Commit 0518db8c authored by Florian Beyer's avatar Florian Beyer
Browse files

translated moveit intermediate task and changed position controller a bit

parent 4dbb9b02
No related branches found
No related tags found
No related merge requests found
%% Cell type:markdown id: tags:
# Learn Environment Panda Robot
Author: NAME
%% Cell type:markdown id: tags:
## Controller_Task
### Position_Controller
> In this task, you will learn ...
>
> - wie du mit einem Position Controller arbeitest, um die Gelenke eines Roboters auf spezifische Positionen zu bewegen.
> - wie man den Position Controller startet
> - wie man eine Nachricht für den Position Controller erstellt
> - wie man die Zielposition sendt und die Bewegung überprüft
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
from controller_manager_msgs.srv import LoadController, SwitchController
from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Lade den Controller:
ROS verwendet den Service /controller_manager/load_controller, um Controller zu laden.
Du musst den Namen des Controllers angeben, den du laden möchtest, in diesem Fall position_joint_trajectory_controller.
Aktiviere den Controller:
Nachdem der Controller geladen ist, musst du ihn starten. Dies geschieht mit dem Service /controller_manager/switch_controller.
Du kannst mehrere Controller gleichzeitig starten und stoppen, indem du deren Namen in den Service-Request übergibst.
Verwende die folgende Vorlage:
Nutze den Service load_controller, um den gewünschten Controller zu laden.
Starte den Service switch_controller, um den Position Controller zu aktivieren.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController
controller_name = 'position_joint_trajectory_controller'
conflicting_controller = 'effort_joint_trajectory_controller'
# Funktion zum Entladen eines Controllers
def unload_controller(controller_name):
rospy.wait_for_service('/controller_manager/switch_controller')
try:
switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
req = SwitchControllerRequest()
req.stop_controllers = [controller_name]
req.strictness = SwitchControllerRequest.BEST_EFFORT
response = switch_controller(req)
assert response.ok, "Controller konnte nicht entladen werden."
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
rospy.wait_for_service('/controller_manager/unload_controller')
try:
unload_srv = rospy.ServiceProxy('/controller_manager/unload_controller', UnloadController)
unload_resp = unload_srv(controller_name)
assert unload_resp.ok, "Controller konnte nicht entladen werden."
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
# Entladen des alten Controllers
unload_controller(conflicting_controller)
# Service für das Laden des Controllers
rospy.wait_for_service('/controller_manager/load_controller')
load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)
response = load_service("position_joint_trajectory_controller")
response = load_service(controller_name)
assert response.ok, "Controller konnte nicht geladen werden."
# Service für das Aktivieren des Controllers
rospy.wait_for_service('/controller_manager/switch_controller')
switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
response = switch_service(start_controllers=['position_joint_trajectory_controller'],
stop_controllers=[], strictness=1)
switch_req = SwitchControllerRequest()
switch_req.start_controllers = [controller_name]
switch_req.strictness = SwitchControllerRequest.BEST_EFFORT
response = switch_service(switch_req)
assert response.ok, "Controller konnte nicht gestartet werden."
print("Position Controller erfolgreich gestartet.")
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Nachrichtentyp:
Der Position Controller empfängt Nachrichten vom Typ trajectory_msgs/JointTrajectory.
Diese Nachricht enthält:
joint_names: Eine Liste der Gelenke, die gesteuert werden sollen.
points: Eine Liste von Positionen, die die Gelenke ansteuern sollen.
Erstelle die Nachricht:
Beginne mit einer JointTrajectory-Nachricht.
Definiere die Gelenke, die du bewegen möchtest, indem du die Namen in der Liste joint_names einträgst.
Füge Zielpositionen hinzu:
Erstelle ein JointTrajectoryPoint, um die Zielpositionen für jedes Gelenk zu definieren.
Ergänze die Felder:
positions: Die Zielpositionen in Radiant (z. B. [0.5, -0.5, 0.0]).
time_from_start: Die Dauer, die der Roboter benötigt, um die Positionen zu erreichen.
Sende die Nachricht:
Veröffentliche die Nachricht auf dem Topic /position_joint_trajectory_controller/command.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Initialisiere ROS
rospy.init_node('position_control', anonymous=True)
# Publisher für das Command-Topic
pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)
# Warte, bis der Publisher bereit ist
rospy.sleep(1)
# Erstelle die Nachricht
traj_msg = JointTrajectory()
traj_msg.joint_names = [...] # TODO: Füge die Gelenknamen des Roboters hier ein
traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
# Definiere die Zielpositionen
point = JointTrajectoryPoint()
point.positions = [...] # TODO: Füge Zielpositionen (in Radiant) für jedes Gelenk hinzu
point.time_from_start = rospy.Duration(...) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll
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
point.time_from_start = rospy.Duration(2.0) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll
# Füge den Punkt zur Trajektorie hinzu
traj_msg.points.append(point)
# Sende die Nachricht
pub.publish(traj_msg)
print("Zielposition wurde gesendet.")
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
In dieser Erweiterung definieren Sie zwei Zielpositionen.
Die erste Zielposition wird erreicht, bevor der Roboter zur zweiten Zielposition übergeht.
Was du tun musst:
Füge eine zweite Zielposition zu traj_msg.points hinzu.
Die zweite Zielposition sollte eine andere Pose ansteuern, um eine sichtbare Bewegung zu demonstrieren.
Planung der Bewegung:
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.
Die Zeitangaben müssen aufeinander aufbauen:
Die erste Zielposition benötigt z. B. 2 Sekunden (time_from_start = 2.0).
Die zweite Zielposition wird nach weiteren 3 Sekunden erreicht (time_from_start = 5.0).
Schritte:
Erstelle eine erste Zielposition: Definiere die Gelenkwinkel und die Dauer.
Erstelle eine zweite Zielposition: Erhöhe die Zeit und ändere die Gelenkwinkel.
Sende beide Punkte: Füge die Punkte zu traj_msg.points hinzu und sende die Nachricht.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
# Nachricht erstellen
traj_msg = JointTrajectory()
traj_msg.joint_names = ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6']
traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
# Erste Zielposition definieren
point1 = JointTrajectoryPoint()
point1.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5]
point1.positions = [0.6, -0.6, 0.2, 0.2, 0.5, -0.5, 0.2]
point1.time_from_start = rospy.Duration(2.0)
traj_msg.points.append(point1)
# Zweite Zielposition definieren
point2 = JointTrajectoryPoint()
point2.positions = [1.0, 0.0, -0.5, 0.0, -0.5, 1.0]
point2.positions = [0.7, -0.2, -0.5, -0.2, -0.5, 0.7, -0.2]
point2.time_from_start = rospy.Duration(5.0)
traj_msg.points.append(point2)
# Nachricht senden
pub.publish(traj_msg)
print("Zwei Zielpositionen wurden gesendet.")
##### YOUR CODE HERE #####
```
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.signal_shutdown("Task completed")
roscpp_shutdown()
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## MoveIt Intermediate
### Task 1
---
>
Ziel dieses Notebooks ist :
- den Roboterarm durch eine Serie von vorgegebenen Positionen (Wegpunkte) im kartesischen Raum zu bewegen
- wie man Bewegungen planen kann, die entlang einer komplexen Trajektorie ablaufen
- wie mehrere Positionen definiert, in eine Trajektorie umgewandelt und schließlich ausgeführt werden können
The goal of this notebook is :
- to move the robotic arm through a series of predetermined positions (waypoints) in Cartesian space
- how to plan movements that run along a complex trajectory
- how multiple positions can be defined, converted into a trajectory and finally executed
>
---
%% Cell type:markdown id: tags:
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.
Then, as usual, we initialize the MoveIt Commander, create a ROS node and initialize the Move Group.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import sys
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown
from geometry_msgs.msg import Pose
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
TODO : Initialisierung beschreiben was man macht
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Initialize the MoveIt Commander
roscpp_initialize(sys.argv)
# Initialize the ROS-Node
rospy.init_node('exercise_6_1', anonymous=True)
rospy.init_node('move_it_intermediate', anonymous=True)
# Initialize the MoveGroup
group = MoveGroupCommander('panda_arm')
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
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).
So your task is to first create a variable current_pose and then store the current pose of the end effector in it.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
# Get the current pose of the end-effector
current_pose = group.get_current_pose().pose
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
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.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Define the waypoints
# Define the waypoints the robot should move to
waypoints = []
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Nun soll der erste Wegpunkt definiert werden. Erstelle also ein neues Objekt von der Klasse pose.
Now you want to define the first waypoint. So create a new object from the class pose.
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.
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.
Füge diesen Wegpunt am Ende der liste waypoints hinzu.
Add this waypunt at the end of the waypoints list.
Tipp : setze diese mithilfe der current pose um
Tip: Do this with the current pose
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
waypoint_1 = Pose()
waypoint_1.position.x = current_pose.position.x + 0.1
waypoint_1.position.y = current_pose.position.y
waypoint_1.position.z = current_pose.position.z
waypoint_1.orientation = current_pose.orientation
waypoints.append(waypoint_1)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Erzeuge als nächstes einen zweiten Wegpunkt , ebenfalls vom Typ Pose.
Next, create a second waypoint, also of the pose type.
Halte hier nun die X- und Z-Positionen aus dem ersten Wegpunkt bei und verschiebe die Y-Position um 0,2 (20 cm).
Wieder gilt, dass die Orientierung aus der current_pose übernommen werden soll.
Now hold the X and Z positions from the first waypoint and shift the Y position by 0.2 (20 cm).
Again, the orientation should be taken from the current_pose.
Füge zuletzt den neuen Wegpunkt zur waypoints-Liste hinzu.
Finally, add the new waypoint to the waypoints list.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
waypoint_2 = Pose()
waypoint_2.position.x = waypoint_1.position.x
waypoint_2.position.y = waypoint_1.position.y + 0.2
waypoint_2.position.z = waypoint_1.position.z
waypoint_2.orientation = current_pose.orientation
waypoints.append(waypoint_2)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Der letzte Wegpunkt soll auch wieder vom Typ Pose sein.
The last waypoint should also be of the type Pose.
Halte hier die X- und Y-Positionen aus dem zweiten Wegpunkt bei und verschiebe die Z-Position um 0,4 (40 cm) nach oben.
Übernimm die Orientierung aus der current_pose.
Hold the X and Y positions from the second waypoint and move the Z position 0.3 (30 cm) up.
Take the orientation from the current_pose.
Füge den neuen Wegpunkt zur waypoints-Liste hinzu.
Add the new waypoint to the waypoints list.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
waypoint_3 = Pose()
waypoint_3.position.x = waypoint_2.position.x
waypoint_3.position.y = waypoint_2.position.y
waypoint_3.position.z = waypoint_2.position.z + 0.4
waypoint_3.position.z = waypoint_2.position.z + 0.3
waypoint_3.orientation = current_pose.orientation
waypoints.append(waypoint_3)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Nun werden Parameter definiert, welche die folgende Bedeutung haben :
Now we define parameters that have the following meaning:
fraction = 0.0, setzt den initialen Wert des berechneten Pfadanteils auf 0,
fraction = 0.0, sets the initial value of the calculated path portion to 0,
max_attempts = 100, legt die maximale Anzahl der Versuche fest, um den Pfad zu berechnen,
max_attempts = 100, sets the maximum number of attempts to calculate the path,
attempts = 0, zählt die Anzahl der Versuche.
attempts = 0, counts the number of attempts.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Compute the Cartesian path
fraction = 0.0
max_attempts = 100
attempts = 0
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
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.
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.
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.
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.
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.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
while fraction < 1.0 and attempts < max_attempts:
(plan, fraction) = group.compute_cartesian_path(waypoints, 0.01, 0.0) # Plan the trajectory
attempts += 1
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Mithilfe der Methode execute wird nun der erstellte plan ausgeführt.
The executed method now executes the created plan.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
if fraction == 1.0:
rospy.loginfo("Successfully computed the Cartesian path. Executing...")
group.execute(plan, wait=True)
rospy.loginfo("Execution completed.")
else:
rospy.logwarn(f"Failed to compute a complete path after {attempts} attempts.")
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Shutdown the ROS node
rospy.signal_shutdown("Task completed")
roscpp_shutdown()
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Learn Environment Panda Robot
Author: NAME
%% Cell type:markdown id: tags:
## Controller_Task
### Position_Controller
> In this task, you will learn ...
>
> - wie du mit einem Position Controller arbeitest, um die Gelenke eines Roboters auf spezifische Positionen zu bewegen.
> - wie man den Position Controller startet
> - wie man eine Nachricht für den Position Controller erstellt
> - wie man die Zielposition sendt und die Bewegung überprüft
%% Cell type:code id: tags:task_cell_1
```
##### DO NOT CHANGE #####
import rospy
from controller_manager_msgs.srv import LoadController, SwitchController
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Lade den Controller:
ROS verwendet den Service /controller_manager/load_controller, um Controller zu laden.
Du musst den Namen des Controllers angeben, den du laden möchtest, in diesem Fall position_joint_trajectory_controller.
Aktiviere den Controller:
Nachdem der Controller geladen ist, musst du ihn starten. Dies geschieht mit dem Service /controller_manager/switch_controller.
Du kannst mehrere Controller gleichzeitig starten und stoppen, indem du deren Namen in den Service-Request übergibst.
Verwende die folgende Vorlage:
Nutze den Service load_controller, um den gewünschten Controller zu laden.
Starte den Service switch_controller, um den Position Controller zu aktivieren.
%% Cell type:code id: tags:task_cell_2
```
##### DO NOT CHANGE #####
import rospy
from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController
controller_name = 'position_joint_trajectory_controller'
conflicting_controller = 'effort_joint_trajectory_controller'
# Funktion zum Entladen eines Controllers
def unload_controller(controller_name):
rospy.wait_for_service('/controller_manager/switch_controller')
try:
switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
req = SwitchControllerRequest()
req.stop_controllers = [controller_name]
req.strictness = SwitchControllerRequest.BEST_EFFORT
response = switch_controller(req)
assert response.ok, "Controller konnte nicht entladen werden."
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
# Nach dem Stoppen auch wirklich entladen:
rospy.wait_for_service('/controller_manager/unload_controller')
try:
unload_srv = rospy.ServiceProxy('/controller_manager/unload_controller', UnloadController)
unload_resp = unload_srv(controller_name)
assert unload_resp.ok, "Controller konnte nicht entladen werden."
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
# Entladen des konfliktierenden Controllers
unload_controller(conflicting_controller)
# Service für das Laden des Controllers
rospy.wait_for_service('/controller_manager/load_controller')
rospy.loginfo('Versuche, /controller_manager/load_controller aufzurufen...')
load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)
response = load_service(controller_name)
rospy.loginfo('LoadController-Antwort: {}'.format(response))
assert response.ok, "Controller konnte nicht geladen werden."
# Service für das Aktivieren des Controllers
rospy.wait_for_service('/controller_manager/switch_controller')
rospy.loginfo('Versuche, /controller_manager/switch_controller aufzurufen...')
switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
switch_req = SwitchControllerRequest()
switch_req.start_controllers = [controller_name]
switch_req.strictness = SwitchControllerRequest.BEST_EFFORT
response = switch_service(switch_req)
rospy.loginfo('SwitchController-Antwort: {}'.format(response))
assert response.ok, "Controller konnte nicht gestartet werden."
print("Position Controller erfolgreich gestartet.")
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Nachrichtentyp:
Der Position Controller empfängt Nachrichten vom Typ trajectory_msgs/JointTrajectory.
Diese Nachricht enthält:
joint_names: Eine Liste der Gelenke, die gesteuert werden sollen.
points: Eine Liste von Positionen, die die Gelenke ansteuern sollen.
Erstelle die Nachricht:
Beginne mit einer JointTrajectory-Nachricht.
Definiere die Gelenke, die du bewegen möchtest, indem du die Namen in der Liste joint_names einträgst.
Füge Zielpositionen hinzu:
Erstelle ein JointTrajectoryPoint, um die Zielpositionen für jedes Gelenk zu definieren.
Ergänze die Felder:
positions: Die Zielpositionen in Radiant (z. B. [0.5, -0.5, 0.0]).
time_from_start: Die Dauer, die der Roboter benötigt, um die Positionen zu erreichen.
Sende die Nachricht:
Veröffentliche die Nachricht auf dem Topic /position_joint_trajectory_controller/command.
%% Cell type:code id: tags:task_cell_3
```
##### DO NOT CHANGE #####
# Initialisiere ROS
rospy.init_node('position_control', anonymous=True)
# Publisher für das Command-Topic
pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)
# Warte, bis der Publisher bereit ist
rospy.sleep(1)
# Erstelle die Nachricht
traj_msg = JointTrajectory()
traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
# Definiere die Zielpositionen
point = JointTrajectoryPoint()
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
point.time_from_start = rospy.Duration(2.0) # TODO: Lege die Zeit fest, bis die Bewegung abgeschlossen sein soll
# Füge den Punkt zur Trajektorie hinzu
traj_msg.points.append(point)
# Sende die Nachricht
pub.publish(traj_msg)
print("Zielposition wurde gesendet.")
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
In dieser Erweiterung definieren Sie zwei Zielpositionen.
Die erste Zielposition wird erreicht, bevor der Roboter zur zweiten Zielposition übergeht.
Was du tun musst:
Füge eine zweite Zielposition zu traj_msg.points hinzu.
Die zweite Zielposition sollte eine andere Pose ansteuern, um eine sichtbare Bewegung zu demonstrieren.
Planung der Bewegung:
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.
Die Zeitangaben müssen aufeinander aufbauen:
Die erste Zielposition benötigt z. B. 2 Sekunden (time_from_start = 2.0).
Die zweite Zielposition wird nach weiteren 3 Sekunden erreicht (time_from_start = 5.0).
Schritte:
Erstelle eine erste Zielposition: Definiere die Gelenkwinkel und die Dauer.
Erstelle eine zweite Zielposition: Erhöhe die Zeit und ändere die Gelenkwinkel.
Sende beide Punkte: Füge die Punkte zu traj_msg.points hinzu und sende die Nachricht.
%% Cell type:code id: tags:task_cell_4,solution_removed_cell
```
##### YOUR CODE HERE #####
raise NotImplementedError()
```
%% Cell type:code id: tags:solution_cell
```
##############################################################\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##############################################################
## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##
# Nachricht erstellen
traj_msg = JointTrajectory()
traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
# Erste Zielposition definieren
point1 = JointTrajectoryPoint()
point1.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]
point1.time_from_start = rospy.Duration(2.0)
traj_msg.points.append(point1)
# Zweite Zielposition definieren
point2 = JointTrajectoryPoint()
point2.positions = [1.0, 0.0, -0.5, 0.0, -0.5, 1.0, 0.0]
point2.time_from_start = rospy.Duration(5.0)
traj_msg.points.append(point2)
# Nachricht senden
pub.publish(traj_msg)
print("Zwei Zielpositionen wurden gesendet.")
## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##
```
%% Cell type:code id: tags:task_cell_5
```
##### DO NOT CHANGE #####
rospy.signal_shutdown("Task completed")
roscpp_shutdown()
##### DO NOT CHANGE #####
```
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment