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

position_controller task added and small changes in describtion of the other tasks

parent 575772f1
No related branches found
No related tags found
No related merge requests found
Showing
with 235 additions and 7 deletions
%% 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 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 #####
# 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")
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)
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
# 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
# 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']
# Erste Zielposition definieren
point1 = JointTrajectoryPoint()
point1.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5]
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.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: %% Cell type:markdown id: tags:
# Educational Plattform Franka Emika Panda robot arm # Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
## MoveIt Basics ## MoveIt Basics
### Task 3 ### Task 3
--- ---
> >
The goal of this notebook is: The goal of this notebook is:
- understand what planning algorithms are - understand what planning algorithms are
- what types there are - what types there are
- how to implement them in code - how to implement them in code
> >
--- ---
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Introduction planning algorithms ### Introduction planning algorithms
#### What are planning algorithms? #### What are planning algorithms?
- Methods used to calculate a sequence of movements or actions that the robot must perform in order to reach a target (e.g. a final position) - Methods used to calculate a sequence of movements or actions that the robot must perform in order to reach a target (e.g. a final position)
- help solve complex problems, such as overcoming obstacles, precise reaching of endpoint - help solve complex problems, such as overcoming obstacles, precise reaching of endpoint
- ensure that movement is efficient, collision-free and physically possible - ensure that movement is efficient, collision-free and physically possible
#### What types of planning algorithms are there ? #### What types of planning algorithms are there ?
Sampling-based algorithms Sampling-based algorithms
- create random sample to find way from start to finish - create random sample to find way from start to finish
- Examples: RTT, RTTConnect - Examples: RTT, RTTConnect
##### Search-based algorithms ##### Search-based algorithms
- use grids or graphs to calculate shortest path - use grids or graphs to calculate shortest path
- Example: A* - Example: A*
##### Optimization based algorithms ##### Optimization based algorithms
- improve existing paths through optimization criteria, such as efficiency - improve existing paths through optimization criteria, such as efficiency
- Examples: CHOMP, STOMP - Examples: CHOMP, STOMP
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
First, we import all the important modules for this task. You already know Rospy and sys from previous tasks. First, we import all the important modules for this task. You already know Rospy and sys from previous tasks.
The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements. The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements.
roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API. roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API.
geometry_msgs.msg is used to provide standardized message formats such as position(pose) and orientation (point) of the robotic arm. geometry_msgs.msg is used to provide standardized message formats such as position(pose) and orientation (point) of the robotic arm.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
import rospy import rospy
import sys import sys
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown
from geometry_msgs.msg import Pose from geometry_msgs.msg import Pose
# Initialize the MoveIt Commander # Initialize the MoveIt Commander
roscpp_initialize(sys.argv) roscpp_initialize(sys.argv)
# Initialize the ROS Node # Initialize the ROS Node
rospy.init_node('exercise_4_1', anonymous=True) rospy.init_node('task3', anonymous=True)
# Initialize MoveGroupCommander # Initialize MoveGroupCommander
group = MoveGroupCommander('panda_arm') group = MoveGroupCommander('panda_arm')
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Next, we want to select the planning algorithm we want to use to calculate the motion. To do this, we use the set_planner_id method to select the specific planning algorithm. Next, we want to select the planning algorithm we want to use to calculate the motion. To do this, we use the set_planner_id method to select the specific planning algorithm.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
# Select the desired planning algorithm # Select the desired planning algorithm
group.set_planner_id("RRTConnectkConfigDefault") group.set_planner_id("RRTConnectkConfigDefault")
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Next, we define the target position of the end effector. The end effector is the part of a robot arm that is attached to the extreme end of the kinematic chain and directly interacts with the environment. It is the functional "tool holder" of the robot, whose job it is to perform specific actions. These actions depend heavily on the task of the robot. Next, we define the target position of the end effector. The end effector is the part of a robot arm that is attached to the extreme end of the kinematic chain and directly interacts with the environment. It is the functional "tool holder" of the robot, whose job it is to perform specific actions. These actions depend heavily on the task of the robot.
The pose class provides a data structure that describes the spatial position and orientation of an object in 3D space. The position contains the x-, y- and z-coordinates, which in the following code defines the target position of the end effector in Cartesian space (in meters). The pose class provides a data structure that describes the spatial position and orientation of an object in 3D space. The position contains the x-, y- and z-coordinates, which in the following code defines the target position of the end effector in Cartesian space (in meters).
The orientation w describes the orientation, which is used for orientation in 3D space. The orientation w describes the orientation, which is used for orientation in 3D space.
A w=cos(θ/2) that is less than 1 indicates that a rotation is taking place. A w=cos(θ/2) that is less than 1 indicates that a rotation is taking place.
The rotation angle θ can be calculated via arccos(w)⋆2. The rotation angle θ can be calculated via arccos(w)⋆2.
w should always be in the range [−1.1] because it is related to cos(θ/2). Values outside this range result in invalid quaternions. w should always be in the range [−1.1] because it is related to cos(θ/2). Values outside this range result in invalid quaternions.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
target_pose = Pose() target_pose = Pose()
target_pose.position.x = 0.1 target_pose.position.x = 0.1
target_pose.position.y = 0.1 target_pose.position.y = 0.1
target_pose.position.z = 0.1 target_pose.position.z = 0.1
target_pose.orientation.w = 1.0 target_pose.orientation.w = 1.0
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now it's about planning and executing the movement of the robotic arm. Now it's about planning and executing the movement of the robotic arm.
The group.go() method executes the planned movement of the robot based on the target pose that was previously set. The group.go() method executes the planned movement of the robot based on the target pose that was previously set.
The wait=True argument means that further execution of the code is blocked (i.e. waits) until the movement is complete. Only after the movement is completed will the next command be executed. The wait=True argument means that further execution of the code is blocked (i.e. waits) until the movement is complete. Only after the movement is completed will the next command be executed.
The group.stop() method stops the movement of the robot immediately. The group.stop() method stops the movement of the robot immediately.
Even if the movement is already complete, this command ensures that no further movements or residual movements (e.g. by inertia or revival) take place. Even if the movement is already complete, this command ensures that no further movements or residual movements (e.g. by inertia or revival) take place.
The group.clear_pose_targets() method removes all pose targets previously defined for the robot. The group.clear_pose_targets() method removes all pose targets previously defined for the robot.
This is very important because target positions that are not removed remain in the memory of the MoveIt object (group) and could be reused inadvertently in later move commands. This is very important because target positions that are not removed remain in the memory of the MoveIt object (group) and could be reused inadvertently in later move commands.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
plan = group.go(wait=True) plan = group.go(wait=True)
group.stop() group.stop()
group.clear_pose_targets() group.clear_pose_targets()
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node ### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released. At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Shutdown the ROS node # Shutdown the ROS node
rospy.signal_shutdown("Task completed") rospy.signal_shutdown("Task completed")
roscpp_shutdown() roscpp_shutdown()
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
......
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
# Educational Plattform Franka Emika Panda robot arm # Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
## MoveIt Basics ## MoveIt Basics
### Task 4 ### Task 4
--- ---
> >
The goal of this notebook is: The goal of this notebook is:
- query and interpret the status of the Franka Emika Panda robotic arm. - query and interpret the status of the Franka Emika Panda robotic arm.
- check the current state of the robot (positions, orientations, joint angle) and understand how to access feedback during or after a movement. - check the current state of the robot (positions, orientations, joint angle) and understand how to access feedback during or after a movement.
> >
--- ---
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
First, we import all the important modules for this task. You already know Rospy and sys from previous tasks. First, we import all the important modules for this task. You already know Rospy and sys from previous tasks.
The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements. The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements.
roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API. roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
import rospy import rospy
import sys import sys
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown
# Initialize the MoveIt Commander # Initialize the MoveIt Commander
roscpp_initialize(sys.argv) roscpp_initialize(sys.argv)
# Initialize the ROS Node # Initialize the ROS Node
rospy.init_node('exercise_4_2', anonymous=True) rospy.init_node('task4', anonymous=True)
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now the MoveGroup for the robot arm `panda_arm` is initialized. Now the MoveGroup for the robot arm `panda_arm` is initialized.
In addition, planning parameters such as the planning algorithm and the number of planning attempts are defined. In addition, planning parameters such as the planning algorithm and the number of planning attempts are defined.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Initialize the MoveGroup # Initialize the MoveGroup
group = MoveGroupCommander('panda_arm') group = MoveGroupCommander('panda_arm')
# Set the planner ID to 'RRTConnectkConfigDefault' # Set the planner ID to 'RRTConnectkConfigDefault'
group.set_planner_id("RRTConnectkConfigDefault") group.set_planner_id("RRTConnectkConfigDefault")
# Set the number of planning attempts to 10 # Set the number of planning attempts to 10
group.set_num_planning_attempts(10) group.set_num_planning_attempts(10)
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Query of current joint angles ### Query of current joint angles
Next, the current joint angles of the robot arm are queried and output in the log. The MoveGroupCommander class provides the get_current_joint_values() method. Next, the current joint angles of the robot arm are queried and output in the log. The MoveGroupCommander class provides the get_current_joint_values() method.
This harvests the current values of the joint angles and returns them as a list. The i-th entry in the list contains the angle of the i-th joint of the robot arm. This harvests the current values of the joint angles and returns them as a list. The i-th entry in the list contains the angle of the i-th joint of the robot arm.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
# Query the current joint values # Query the current joint values
joint_values = group.get_current_joint_values() joint_values = group.get_current_joint_values()
rospy.loginfo("Current Joint Values: ") rospy.loginfo("Current Joint Values: ")
for i, joint in enumerate(joint_values): for i, joint in enumerate(joint_values):
rospy.loginfo(f"Joint {i+1}: {joint:.2f} rad") rospy.loginfo(f"Joint {i+1}: {joint:.2f} rad")
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Query the current end effector position ### Query the current end effector position
In the next step, the current pose of the end effector is queried and output in the log. The MoveGroupCommander class provides the get_current_pose() method. This method is used to determine the position and orientation of the end effector's space relative to a defined frame of reference. In the next step, the current pose of the end effector is queried and output in the log. The MoveGroupCommander class provides the get_current_pose() method. This method is used to determine the position and orientation of the end effector's space relative to a defined frame of reference.
The get_current_pose() method returns a message of the type PoseStamped. This contains the position as x -, y - and z - coordinates of the end effector, the orientation describes the orientation of the end effector given as quaternion (x, y, z, w) and much more information. The get_current_pose() method returns a message of the type PoseStamped. This contains the position as x -, y - and z - coordinates of the end effector, the orientation describes the orientation of the end effector given as quaternion (x, y, z, w) and much more information.
.pose is used to access the Pose attribute, which contains only the information about the position and orientation of the end effector. This attribute is of the Pose type. .pose is used to access the Pose attribute, which contains only the information about the position and orientation of the end effector. This attribute is of the Pose type.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
# Query the current end-effector pose # Query the current end-effector pose
pose = group.get_current_pose().pose pose = group.get_current_pose().pose
rospy.loginfo(f"Endeffector Position: x={pose.position.x:.3f}, y={pose.position.y:.3f}, z={pose.position.z:.3f}") rospy.loginfo(f"Endeffector Position: x={pose.position.x:.3f}, y={pose.position.y:.3f}, z={pose.position.z:.3f}")
rospy.loginfo(f"Endeffector Orientation: x={pose.orientation.x:.3f}, y={pose.orientation.y:.3f}, z={pose.orientation.z:.3f}, w={pose.orientation.w:.3f}") rospy.loginfo(f"Endeffector Orientation: x={pose.orientation.x:.3f}, y={pose.orientation.y:.3f}, z={pose.orientation.z:.3f}, w={pose.orientation.w:.3f}")
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
The pose of the end effector is crucial to check the current condition of the robotic arm. The pose of the end effector is crucial to check the current condition of the robotic arm.
The position is needed to ensure that the end effector is in the right place in the room. The position is needed to ensure that the end effector is in the right place in the room.
The orientation is essential when the end effector has to act in a certain orientation, e.g. to grasp an object correctly. The orientation is essential when the end effector has to act in a certain orientation, e.g. to grasp an object correctly.
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node ### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released. At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Shutdown the ROS node # Shutdown the ROS node
rospy.signal_shutdown("Task completed") rospy.signal_shutdown("Task completed")
roscpp_shutdown() roscpp_shutdown()
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
......
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
# Educational Plattform Franka Emika Panda robot arm # Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
## MoveIt Objects ## MoveIt Objects
### Task 1 ### Task 1
--- ---
> >
The goal of this notebook is: The goal of this notebook is:
- to understand how to create objects - to understand how to create objects
- and how to add them to the scene - and how to add them to the scene
> >
--- ---
%% Cell type:markdown id: tags: %% 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 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. 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: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
import rospy import rospy
import sys import sys
from geometry_msgs.msg import PoseStamped from geometry_msgs.msg import PoseStamped
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now ROS and MoveIt will be initialized again, as well as here the new planning scene. Now ROS and MoveIt will be initialized again, as well as here the new planning scene.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Initialize the MoveIt Commander # Initialize the MoveIt Commander
roscpp_initialize(sys.argv) roscpp_initialize(sys.argv)
# Initialize the ROS Node # Initialize the ROS Node
rospy.init_node('exercise_5_1', anonymous=True) rospy.init_node('taks1', anonymous=True)
# Initialize PlanningScene # Initialize PlanningScene
scene = PlanningSceneInterface() scene = PlanningSceneInterface()
rospy.sleep(1) rospy.sleep(1)
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% 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 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: This object contains two main components:
- header: information about the coordinate frame and time stamp. - header: information about the coordinate frame and time stamp.
- pose: The actual position (translation) and orientation (rotation) of the object. - pose: The actual position (translation) and orientation (rotation) of the object.
Now the frame_id is set in the header of the PoseStamped-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. "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: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
box_pose = PoseStamped() box_pose = PoseStamped()
box_pose.header.frame_id = "panda_link0" box_pose.header.frame_id = "panda_link0"
box_pose.pose.position.x = 0.4 box_pose.pose.position.x = 0.4
box_pose.pose.position.y = 0.0 box_pose.pose.position.y = 0.0
box_pose.pose.position.z = 0.1 box_pose.pose.position.z = 0.1
box_pose.pose.orientation.w = 1.0 box_pose.pose.orientation.w = 1.0
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% 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. 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 : 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 - 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 - 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 - size (type : tuple): a tuple describing the size of the box
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# adding a 5cmx5cmx5cm cube # adding a 5cmx5cmx5cm cube
scene.add_box("box_1", box_pose, size=(0.05, 0.05, 0.05)) scene.add_box("box_1", box_pose, size=(0.05, 0.05, 0.05))
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Exercise 1: 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. 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. Give it a name: box_2.
Proceed as follows: Proceed as follows:
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Create a new PoseStamped object and define the coordinates of the new object. Create a new PoseStamped object and define the coordinates of the new object.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
box_pose_2 = PoseStamped() box_pose_2 = PoseStamped()
box_pose_2.header.frame_id = "panda_link0" box_pose_2.header.frame_id = "panda_link0"
box_pose_2.pose.position.x = 1.0 box_pose_2.pose.position.x = 1.0
box_pose_2.pose.position.y = 1.0 box_pose_2.pose.position.y = 1.0
box_pose_2.pose.position.z = 1.0 box_pose_2.pose.position.z = 1.0
box_pose_2.pose.orientation.w = 1.0 box_pose_2.pose.orientation.w = 1.0
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now add the object with the specified dimensions of the scene. Now add the object with the specified dimensions of the scene.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
scene.add_box("box_2", box_pose_2, size=(0.1, 0.1, 0.1)) scene.add_box("box_2", box_pose_2, size=(0.1, 0.1, 0.1))
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Exercise 2: 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. 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: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
cylinder_pose = PoseStamped() cylinder_pose = PoseStamped()
cylinder_pose.header.frame_id = "panda_link0" cylinder_pose.header.frame_id = "panda_link0"
cylinder_pose.pose.position.x = 2.0 cylinder_pose.pose.position.x = 2.0
cylinder_pose.pose.position.y = 0.0 cylinder_pose.pose.position.y = 0.0
cylinder_pose.pose.position.z = 4.0 cylinder_pose.pose.position.z = 4.0
cylinder_pose.pose.orientation.x = 0.0 cylinder_pose.pose.orientation.x = 0.0
cylinder_pose.pose.orientation.y = 0.7071 cylinder_pose.pose.orientation.y = 0.7071
cylinder_pose.pose.orientation.z = 0.0 cylinder_pose.pose.orientation.z = 0.0
cylinder_pose.pose.orientation.w = 0.7071 cylinder_pose.pose.orientation.w = 0.7071
radius = 0.2 radius = 0.2
height = 1.0 height = 1.0
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now add the cylinder with the defined coordinates and orientation to the scene. Now add the cylinder with the defined coordinates and orientation to the scene.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
scene.add_cylinder("cylinder", cylinder_pose, height=height, radius=radius) scene.add_cylinder("cylinder", cylinder_pose, height=height, radius=radius)
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node ### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released. At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Shutdown the ROS node # Shutdown the ROS node
rospy.signal_shutdown("Task completed") rospy.signal_shutdown("Task completed")
roscpp_shutdown() roscpp_shutdown()
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
......
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
# Educational Plattform Franka Emika Panda robot arm # Educational Plattform Franka Emika Panda robot arm
Author: uninh, uqwfa, ultck Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
## MoveIt Objects ## MoveIt Objects
### Task 2 ### Task 2
--- ---
> >
The goal of this notebook is: The goal of this notebook is:
- get to know new classes for creating objects - get to know new classes for creating objects
- Stacking objects on top of each other - Stacking objects on top of each other
> >
--- ---
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
First, all necessary packages are imported. First, all necessary packages are imported.
The SolidPrimitive class offers the ability to create simple geometric objects, such as boxes, cylinders and cones. It has the two attributes Type, which determine the type of object (e.g. BOX, CYLINDER) and Dimension, which determine the size of the object. The SolidPrimitive class offers the ability to create simple geometric objects, such as boxes, cylinders and cones. It has the two attributes Type, which determine the type of object (e.g. BOX, CYLINDER) and Dimension, which determine the size of the object.
The CollisionObject class is used to describe the position and orientation of the object and is used to define obstacles and objects in the scene that are taken into account in the collision check. The CollisionObject class is used to describe the position and orientation of the object and is used to define obstacles and objects in the scene that are taken into account in the collision check.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
import sys import sys
import rospy import rospy
from moveit_commander import roscpp_initialize, roscpp_shutdown, PlanningSceneInterface from moveit_commander import roscpp_initialize, roscpp_shutdown, PlanningSceneInterface
from moveit_msgs.msg import CollisionObject from moveit_msgs.msg import CollisionObject
from shape_msgs.msg import SolidPrimitive from shape_msgs.msg import SolidPrimitive
from geometry_msgs.msg import Pose from geometry_msgs.msg import Pose
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now you initialize the ROS node, MoveIt Commander and the PlanningSceneInterface. Now you initialize the ROS node, MoveIt Commander and the PlanningSceneInterface.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Initialize the MoveIt Commander # Initialize the MoveIt Commander
roscpp_initialize(sys.argv) roscpp_initialize(sys.argv)
# Initialize the ROS Node # Initialize the ROS Node
rospy.init_node('exercise_5_2', anonymous=True) rospy.init_node('task2', anonymous=True)
# Initialize the PlanningSceneInterface # Initialize the PlanningSceneInterface
planning_scene_interface = PlanningSceneInterface() planning_scene_interface = PlanningSceneInterface()
# Wait for the planning scene interface to initialize # Wait for the planning scene interface to initialize
rospy.sleep(2) rospy.sleep(2)
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now create the first object, a rectangle with the following attributes : Now create the first object, a rectangle with the following attributes :
Size: Size:
- width 20 cm - width 20 cm
- Length 40 cm - Length 40 cm
- Height 40 cm - Height 40 cm
Coordinates: Coordinates:
- (0.5, 0.0, 0.2) - (0.5, 0.0, 0.2)
Directions: Directions:
- Neutral - Neutral
Important : this one has the id : rectangle_1 Important : this one has the id : rectangle_1
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
# rectangle_1 # rectangle_1
rectangle_1 = CollisionObject() rectangle_1 = CollisionObject()
rectangle_1.id = "rectangle_1" rectangle_1.id = "rectangle_1"
rectangle_1.header.frame_id = "panda_link0" rectangle_1.header.frame_id = "panda_link0"
primitive1 = SolidPrimitive() primitive1 = SolidPrimitive()
primitive1.type = SolidPrimitive.BOX primitive1.type = SolidPrimitive.BOX
primitive1.dimensions = [0.2, 0.4, 0.4] primitive1.dimensions = [0.2, 0.4, 0.4]
rectangle_1.primitives.append(primitive1) rectangle_1.primitives.append(primitive1)
pose1 = Pose() pose1 = Pose()
pose1.position.x = 0.5 pose1.position.x = 0.5
pose1.position.y = 0.0 pose1.position.y = 0.0
pose1.position.z = 0.2 pose1.position.z = 0.2
pose1.orientation.w = 1.0 pose1.orientation.w = 1.0
rectangle_1.primitive_poses.append(pose1) rectangle_1.primitive_poses.append(pose1)
rectangle_1.operation = CollisionObject.ADD rectangle_1.operation = CollisionObject.ADD
# add rectangle_1 to the planning scene # add rectangle_1 to the planning scene
planning_scene_interface.add_object(rectangle_1) planning_scene_interface.add_object(rectangle_1)
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Next, create the second rectangle, with the same attributes as the first: Next, create the second rectangle, with the same attributes as the first:
Size: Size:
- width 20 cm - width 20 cm
- Length 40 cm - Length 40 cm
- Height 40 cm - Height 40 cm
Coordinates: Coordinates:
- (0.5, 0.0, 0.2) - (0.5, 0.0, 0.2)
Directions: Directions:
- Neutral - Neutral
Important : this one has the id : rectangle_2 Important : this one has the id : rectangle_2
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
# rectangle_2 # rectangle_2
rectangle_2 = CollisionObject() rectangle_2 = CollisionObject()
rectangle_2.id = "rectangle_2" rectangle_2.id = "rectangle_2"
rectangle_2.header.frame_id = "panda_link0" rectangle_2.header.frame_id = "panda_link0"
primitive2 = SolidPrimitive() primitive2 = SolidPrimitive()
primitive2.type = SolidPrimitive.BOX primitive2.type = SolidPrimitive.BOX
primitive2.dimensions = [0.4, 0.2, 0.4] primitive2.dimensions = [0.4, 0.2, 0.4]
rectangle_2.primitives.append(primitive2) rectangle_2.primitives.append(primitive2)
pose2 = Pose() pose2 = Pose()
pose2.position.x = 0.0 pose2.position.x = 0.0
pose2.position.y = 0.5 pose2.position.y = 0.5
pose2.position.z = 0.2 pose2.position.z = 0.2
pose2.orientation.w = 1.0 pose2.orientation.w = 1.0
rectangle_2.primitive_poses.append(pose2) rectangle_2.primitive_poses.append(pose2)
rectangle_2.operation = CollisionObject.ADD rectangle_2.operation = CollisionObject.ADD
# add rectangle_2 to the planning scene # add rectangle_2 to the planning scene
planning_scene_interface.add_object(rectangle_2) planning_scene_interface.add_object(rectangle_2)
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Finally, create a rod which is placed on one of the rectangles and which has the following attributes: Finally, create a rod which is placed on one of the rectangles and which has the following attributes:
Size: Size:
- width 2 cm - width 2 cm
- Length 2 cm - Length 2 cm
- height 20 cm - height 20 cm
Coordinates: Coordinates:
- (0.5, 0.0, 0.5) - (0.5, 0.0, 0.5)
Directions: Directions:
- Neutral - Neutral
Important : this one has the id : target Important : this one has the id : target
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
# target_object # target_object
target_object = CollisionObject() target_object = CollisionObject()
target_object.id = "target" target_object.id = "target"
target_object.header.frame_id = "panda_link0" target_object.header.frame_id = "panda_link0"
primitive3 = SolidPrimitive() primitive3 = SolidPrimitive()
primitive3.type = SolidPrimitive.BOX primitive3.type = SolidPrimitive.BOX
primitive3.dimensions = [0.02, 0.02, 0.2] primitive3.dimensions = [0.02, 0.02, 0.2]
target_object.primitives.append(primitive3) target_object.primitives.append(primitive3)
pose3 = Pose() pose3 = Pose()
pose3.position.x = 0.5 pose3.position.x = 0.5
pose3.position.y = 0.0 pose3.position.y = 0.0
pose3.position.z = 0.5 pose3.position.z = 0.5
pose3.orientation.w = 1.0 pose3.orientation.w = 1.0
target_object.primitive_poses.append(pose3) target_object.primitive_poses.append(pose3)
target_object.operation = CollisionObject.ADD target_object.operation = CollisionObject.ADD
# add target_object to the planning scene # add target_object to the planning scene
planning_scene_interface.add_object(target_object) planning_scene_interface.add_object(target_object)
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node ### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released. At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Shutdown the ROS node # Shutdown the ROS node
rospy.signal_shutdown("Task completed") rospy.signal_shutdown("Task completed")
roscpp_shutdown() roscpp_shutdown()
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
......
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
# Educational Plattform Panda Robot # Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
## MoveIt Objects ## MoveIt Objects
### Task 3 ### Task 3
--- ---
> >
The goal of this notebook is: The goal of this notebook is:
- to understand how to remove objects from a scene - to understand how to remove objects from a scene
- to check which objects are currently in the scene - to check which objects are currently in the scene
> >
--- ---
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
We import the same packages we did in the previous task. We import the same packages we did in the previous task.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
import rospy import rospy
import sys import sys
from geometry_msgs.msg import PoseStamped from geometry_msgs.msg import PoseStamped
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now ROS, MoveIt and the PlanningScene will be initialized. Now ROS, MoveIt and the PlanningScene will be initialized.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Initialize the MoveIt Commander # Initialize the MoveIt Commander
roscpp_initialize(sys.argv) roscpp_initialize(sys.argv)
# Initialize the ROS Node # Initialize the ROS Node
rospy.init_node('exercise_5_1', anonymous=True) rospy.init_node('task3', anonymous=True)
# Initialize PlanningScene # Initialize PlanningScene
scene = PlanningSceneInterface() scene = PlanningSceneInterface()
rospy.sleep(1) rospy.sleep(1)
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now remove the two objects added in the previous task of the scene. This is possible using the method provided by the PlanningSceneInterface class, remove_world_object(name), where name is the sting name of the object to be removed. Now remove the two objects added in the previous task of the scene. This is possible using the method provided by the PlanningSceneInterface class, remove_world_object(name), where name is the sting name of the object to be removed.
You can also remove all objects in the scene at once by calling remove_world_object() without parameter. You can also remove all objects in the scene at once by calling remove_world_object() without parameter.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
scene.remove_world_object("box_1") scene.remove_world_object("box_1")
scene.remove_world_object("box_2") scene.remove_world_object("box_2")
scene.remove_world_object("cylinder") scene.remove_world_object("cylinder")
# Alternativ : remove_world_object() # Alternativ : remove_world_object()
##### YOUR CODE HERE ##### ##### YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
Now check that all objects have been removed from the scene. This is where the get_known_object_names() method, which is also provided by the PlanningSceneInterface class, comes in handy. This method returns a list of strings, with each string representing the name of a known object in the scene. Now check that all objects have been removed from the scene. This is where the get_known_object_names() method, which is also provided by the PlanningSceneInterface class, comes in handy. This method returns a list of strings, with each string representing the name of a known object in the scene.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### WRITE YOUR CODE HERE ##### ##### WRITE YOUR CODE HERE #####
object_names = scene.get_known_object_names() object_names = scene.get_known_object_names()
rospy.loginfo(len(object_names) == 0) rospy.loginfo(len(object_names) == 0)
##### WRITE YOUR CODE HERE ##### ##### WRITE YOUR CODE HERE #####
``` ```
%% Cell type:markdown id: tags: %% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node ### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released. At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` ```
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
# Shutdown the ROS node # Shutdown the ROS node
rospy.signal_shutdown("Task completed") rospy.signal_shutdown("Task completed")
roscpp_shutdown() roscpp_shutdown()
##### DO NOT CHANGE ##### ##### DO NOT CHANGE #####
``` ```
......
...@@ -125,16 +125,22 @@ ...@@ -125,16 +125,22 @@
] ]
}, },
{ {
"title": "Trajectory Controller", "title": "Controller Basics",
"folder": "/controller/controller_task", "folder": "/controller/controller_task",
"topic": "Controller", "topic": "Controller",
"difficulty": "beginner", "difficulty": "beginner",
"subtasks": [ "subtasks": [
{ {
"title": "Task 1", "title": "Task 1",
"description": "TODO: Add Subtask Description Subtask 1.", "description": "Understand the basics of the trajectory controller",
"solution_file": "/trajectory_controller.ipynb", "solution_file": "/trajectory_controller.ipynb",
"evaluation_file": "/trajectory_controller.py" "evaluation_file": "/trajectory_controller.py"
},
{
"title": "Task 2",
"description": "Undersatnd the basics of the position controller",
"solution_file": "/position_controller.ipynb",
"evaluation_file": "/position_controller.py"
} }
] ]
}, },
......
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