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

added moveit intermediate

parent 1dd5092d
No related branches found
No related tags found
No related merge requests found
%% Cell type:markdown id: tags:
# Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck
### Exercise_6_1 :
%% 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
>
---
%% Cell type:markdown id: tags:
TODO : Beschreiben der Funktionalität der Pakete, wenn man nicht in vorheriger Aufgabe schon gemacht hat
%% 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)
# Initialize the MoveGroup
arm_group = MoveGroupCommander('panda_arm')
group = MoveGroupCommander('panda_arm')
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Todo : Beschreibung
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
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
##### YOUR CODE HERE #####
# Get the current pose of the end-effector
current_pose = arm_group.get_current_pose().pose
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.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Define the waypoints
waypoints = []
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Todo : Beschreibung
Nun soll der erste Wegpunkt definiert werden. Erstelle also ein neues Objekt von der Klasse 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.
Füge diesen Wegpunt am Ende der liste waypoints hinzu.
Tipp : setze diese mithilfe der current pose um
%% Cell type:code id: tags:
```
# Waypoint 1: Slightly move along the X-axis
##### 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:
Todo : Beschreibung
Erzeuge als nächstes einen zweiten Wegpunkt , ebenfalls vom Typ Pose.
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.
Füge zuletzt den neuen Wegpunkt zur waypoints-Liste hinzu.
%% Cell type:code id: tags:
```
# Waypoint 2: Move along the Y-axis
##### YOUR CODE HERE #####
waypoint_2 = Pose()
waypoint_2.position.x = waypoint_1.position.x
waypoint_2.position.y = waypoint_1.position.y + 0.1
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:
Todo : Beschreibung
Der letzte Wegpunkt soll auch wieder vom Typ Pose sein.
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.
Füge den neuen Wegpunkt zur waypoints-Liste hinzu.
%% Cell type:code id: tags:
```
# Waypoint 3: Move upwards along the Z-axis
##### 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.1
waypoint_3.position.z = waypoint_2.position.z + 0.4
waypoint_3.orientation = current_pose.orientation
waypoints.append(waypoint_3)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Todo : Beschreibung
Nun werden Parameter definiert, welche die folgende Bedeutung haben :
fraction = 0.0, setzt den initialen Wert des berechneten Pfadanteils auf 0,
max_attempts = 100, legt die maximale Anzahl der Versuche fest, um den Pfad zu berechnen,
attempts = 0, zählt die Anzahl der Versuche.
%% 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.
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.
Erhöhe am Ende innerhalb der Schleife die Anzahl der Versuche um 1.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
while fraction < 1.0 and attempts < max_attempts:
(plan, fraction) = arm_group.compute_cartesian_path(waypoints, 0.01, 0.0) # Plan the trajectory
(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.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
if fraction == 1.0:
rospy.loginfo("Successfully computed the Cartesian path. Executing...")
arm_group.execute(plan, wait=True)
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:
# Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## MoveIt Objects
### Task 1
---
>
The goal of this notebook is:
- to understand how to create objects
- and how to add them to the scene
>
---
%% Cell type:markdown id: tags:
The class PoseStamped extends the class PoseStamped, already known in Exercise_4_1, and is thus used to capture position and orientation and to associate them with a point in time, i.e. at which point in time the pose was captured.
The PlanningSceneInterface is responsible for managing the planning scene, i.e. the environment in which the robot works. This environment contains all the obstacles and objects that need to be taken into account when planning movement.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import sys
from geometry_msgs.msg import PoseStamped
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now ROS and MoveIt will be initialized again, as well as here the new planning scene.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Initialize the MoveIt Commander
roscpp_initialize(sys.argv)
# Initialize the ROS Node
rospy.init_node('exercise_5_1', anonymous=True)
# Initialize PlanningScene
scene = PlanningSceneInterface()
rospy.sleep(1)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
This section defines the pose of an object, which is later added to the planning environment. To do this, an object of the class PoseStamped, which describes a combination of spatial position and orientation within a specific coordinate frame, is created.
This object contains two main components:
- header: information about the coordinate frame and time stamp.
- pose: The actual position (translation) and orientation (rotation) of the object.
Now the frame_id is set in the header of the PoseStamped-object.
"panda_link0" is the base frame of the robotic arm. All position and orientation information refers to this coordinate frame.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
box_pose = PoseStamped()
box_pose.header.frame_id = "panda_link0"
box_pose.pose.position.x = 0.4
box_pose.pose.position.y = 0.0
box_pose.pose.position.z = 0.1
box_pose.pose.orientation.w = 1.0
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
In the next section, a cube object is added to the planning environment. The PlanningSceneInterface class provides the add_box() method, which adds the object (a cube, i.e. 3-dimensional rectangular object) based on the previously defined position and orientation data of the scene.
The add_box(name, pose, size) method must be given the following arguments :
- name (type : string): a string that describes the name of the object to be added
- pose (type: PoseStamped): the pose of the object, which consists of position and orientation
- size (type : tuple): a tuple describing the size of the box
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# adding a 5cmx5cmx5cm cube
scene.add_box("box_1", box_pose, size=(0.05, 0.05, 0.05))
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Exercise 1:
Creates a cube on the coordinates (1.0,1.0,1.0), no rotation and with the side length 10cm and adds it to the planning scene.
Give it a name: box_2.
Proceed as follows:
%% Cell type:markdown id: tags:
Create a new PoseStamped object and define the coordinates of the new object.
%% Cell type:code id: tags:
```
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
box_pose_2 = PoseStamped()
box_pose_2.header.frame_id = "panda_link0"
box_pose_2.pose.position.x = 1.0
box_pose_2.pose.position.y = 1.0
box_pose_2.pose.position.z = 1.0
box_pose_2.pose.orientation.w = 1.0
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Now add the object with the specified dimensions of the scene.
%% Cell type:code id: tags:
```
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
scene.add_box("box_2", box_pose_2, size=(0.1, 0.1, 0.1))
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Exercise 2:
Created a cylinder with radius 20 cm, height 1 m, which has the x coordinate 2, y coordinate 0 and z coordinate 4 and which is rotated by 90 degrees about the y axis.
%% Cell type:code id: tags:
```
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
cylinder_pose = PoseStamped()
cylinder_pose.header.frame_id = "panda_link0"
cylinder_pose.pose.position.x = 2.0
cylinder_pose.pose.position.y = 0.0
cylinder_pose.pose.position.z = 4.0
cylinder_pose.pose.orientation.x = 0.0
cylinder_pose.pose.orientation.y = 0.7071
cylinder_pose.pose.orientation.z = 0.0
cylinder_pose.pose.orientation.w = 0.7071
radius = 0.2
height = 1.0
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Now add the cylinder with the defined coordinates and orientation to the scene.
%% Cell type:code id: tags:
```
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
scene.add_cylinder("cylinder", cylinder_pose, height=height, radius=radius)
##### WRITE YOUR CODE HERE #####
##### YOUR CODE HERE #####
```
%% 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 #####
```
......
......@@ -111,30 +111,30 @@
]
},
{
"title": "Trajectory Controller",
"folder": "/controller/controller_task",
"topic": "Controller",
"difficulty": "beginner",
"title": "MoveIt Intermediate",
"folder": "/move_it/move_it_intermediate",
"topic": "MoveIt",
"difficulty": "intermediate",
"subtasks": [
{
"title": "Task 1",
"description": "TODO: Add Subtask Description Subtask 1.",
"solution_file": "/trajectory_controller.ipynb",
"evaluation_file": "/trajectory_controller.py"
"title": "Task 1 ",
"description": "move the robotic arm through a series of positions (waypoints)",
"solution_file": "/move_it_intermediate_1.ipynb",
"evaluation_file": "/move_it_intermediate_eval_1.py"
}
]
},
{
"title": "Task 6 (TODO: Rename)",
"topic": "Topic 2",
"title": "Trajectory Controller",
"folder": "/controller/controller_task",
"topic": "Controller",
"difficulty": "beginner",
"folder": "/beginner/exercise_6",
"subtasks": [
{
"title": "Subtask 6.1 (TODO: Rename)",
"title": "Task 1",
"description": "TODO: Add Subtask Description Subtask 1.",
"solution_file": "/exercise_6_1.ipynb",
"evaluation_file": "/exercise_6_1_eval.py"
"solution_file": "/trajectory_controller.ipynb",
"evaluation_file": "/trajectory_controller.py"
}
]
},
......
%% 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
>
---
%% Cell type:markdown id: tags:
TODO : Beschreiben der Funktionalität der Pakete, wenn man nicht in vorheriger Aufgabe schon gemacht hat
%% Cell type:code id: tags:task_cell_1
```
##### 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:task_cell_2
```
##### DO NOT CHANGE #####
# Initialize the MoveIt Commander
roscpp_initialize(sys.argv)
# Initialize the ROS-Node
rospy.init_node('exercise_6_1', 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
%% Cell type:code id: tags:task_cell_3,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 ↓↓↓↓ ##
# Get the current pose of the end-effector
current_pose = group.get_current_pose().pose
## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##
```
%% Cell type:markdown id: tags:
Füge alle Wegpunkte, die der Roboterarm ablaufen soll der hier definierten liste waypoints hinzu.
%% Cell type:code id: tags:task_cell_4
```
##### DO NOT CHANGE #####
# Define the waypoints
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.
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.
Füge diesen Wegpunt am Ende der liste waypoints hinzu.
Tipp : setze diese mithilfe der current pose um
%% Cell type:code id: tags:task_cell_5,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 ↓↓↓↓ ##
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)
## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##
```
%% Cell type:markdown id: tags:
Erzeuge als nächstes einen zweiten Wegpunkt , ebenfalls vom Typ Pose.
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.
Füge zuletzt den neuen Wegpunkt zur waypoints-Liste hinzu.
%% Cell type:code id: tags:task_cell_6,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 ↓↓↓↓ ##
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)
## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##
```
%% Cell type:markdown id: tags:
Der letzte Wegpunkt soll auch wieder vom Typ Pose sein.
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.
Füge den neuen Wegpunkt zur waypoints-Liste hinzu.
%% Cell type:code id: tags:task_cell_7,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 ↓↓↓↓ ##
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.orientation = current_pose.orientation
waypoints.append(waypoint_3)
## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##
```
%% Cell type:markdown id: tags:
Nun werden Parameter definiert, welche die folgende Bedeutung haben :
fraction = 0.0, setzt den initialen Wert des berechneten Pfadanteils auf 0,
max_attempts = 100, legt die maximale Anzahl der Versuche fest, um den Pfad zu berechnen,
attempts = 0, zählt die Anzahl der Versuche.
%% Cell type:code id: tags:task_cell_8
```
##### 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.
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.
Erhöhe am Ende innerhalb der Schleife die Anzahl der Versuche um 1.
%% Cell type:code id: tags:task_cell_9,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 ↓↓↓↓ ##
while fraction < 1.0 and attempts < max_attempts:
(plan, fraction) = group.compute_cartesian_path(waypoints, 0.01, 0.0) # Plan the trajectory
attempts += 1
## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##
```
%% Cell type:markdown id: tags:
Mithilfe der Methode execute wird nun der erstellte plan ausgeführt.
%% Cell type:code id: tags:task_cell_10
```
##### 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:task_cell_11
```
##### DO NOT CHANGE #####
# Shutdown the ROS node
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