Hands on Object Relational Mapping in PyCram

This tutorial will walk you through the serialization of a minimal plan in pycram. First we will import sqlalchemy, create an in memory database and connect a session to it.

[1]:
import sqlalchemy
import sqlalchemy.orm

engine = sqlalchemy.create_engine("sqlite+pysqlite:///:memory:", echo=False)
session = sqlalchemy.orm.Session(bind=engine)
session
[1]:
<sqlalchemy.orm.session.Session at 0x7ffae253f130>

Next we create the database schema using the sqlalchemy functionality. For that we need to import the base class of pycram.orm.

[2]:
import pycram.orm.base
import pycram.orm.action_designator
pycram.orm.base.Base.metadata.create_all(engine)
session.commit()
pybullet build time: May 20 2022 19:44:17
Unknown attribute "type" in /robot[@name='pr2']/link[@name='base_laser_link']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='laser_tilt_link']
[WARN] [1706547069.541495]: Failed to import Giskard messages
[WARN] [1706547069.546682]: Could not import RoboKudo messages, RoboKudo interface could not be initialized

Next we will write a simple plan where the robot parks his arms and then moves somewhere. We will construct a TaskTree around it such that we can serialize it later. As usual, we first create a world and then define the plan. By doing so, we obtain the task tree.

[3]:
from pycram.designators.action_designator import *
from pycram.designators.location_designator import *
from pycram.process_module import simulated_robot
from pycram.enums import Arms, ObjectType
from pycram.task import with_tree
import pycram.task
from pycram.bullet_world import Object
from pycram.designators.object_designator import *
from pycram.pose import Pose
import anytree

world = BulletWorld()
pr2 = Object("pr2", ObjectType.ROBOT, "pr2.urdf")
kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf")
milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9]))
cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95]))
milk_desig = ObjectDesignatorDescription(names=["milk"])
cereal_desig = ObjectDesignatorDescription(names=["cereal"])
robot_desig = ObjectDesignatorDescription(names=["pr2"]).resolve()
kitchen_desig = ObjectDesignatorDescription(names=["kitchen"])

@with_tree
def plan():
    with simulated_robot:
        ParkArmsActionPerformable(Arms.BOTH).perform()
        MoveTorsoAction([0.3]).resolve().perform()
        pickup_pose = CostmapLocation(target=cereal_desig.resolve(), reachable_for=robot_desig).resolve()
        pickup_arm = pickup_pose.reachable_arms[0]
        NavigateAction(target_locations=[pickup_pose.pose]).resolve().perform()
        PickUpAction(object_designator_description=cereal_desig, arms=[pickup_arm], grasps=["front"]).resolve().perform()
        ParkArmsAction([Arms.BOTH]).resolve().perform()

        place_island = SemanticCostmapLocation("kitchen_island_surface", kitchen_desig.resolve(),
                                           cereal_desig.resolve()).resolve()

        place_stand = CostmapLocation(place_island.pose, reachable_for=robot_desig, reachable_arm=pickup_arm).resolve()

        NavigateAction(target_locations=[place_stand.pose]).resolve().perform()

        PlaceAction(cereal_desig, target_locations=[place_island.pose], arms=[pickup_arm]).resolve().perform()

        ParkArmsActionPerformable(Arms.BOTH).perform()

plan()

# set description of what we are doing
pycram.orm.base.ProcessMetaData().description = "Tutorial for getting familiar with the ORM."
task_tree = pycram.task.task_tree
print(anytree.RenderTree(task_tree))
Unknown tag "material" in /robot[@name='plane']/link[@name='planeLink']/collision[1]
Unknown tag "contact" in /robot[@name='plane']/link[@name='planeLink']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='base_laser_link']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='laser_tilt_link']
Unknown tag "material" in /robot[@name='plane']/link[@name='planeLink']/collision[1]
Unknown tag "contact" in /robot[@name='plane']/link[@name='planeLink']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='base_laser_link']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='laser_tilt_link']
Scalar element defined multiple times: limit
Scalar element defined multiple times: limit
startThreads creating 1 threads.
starting thread 0
started thread 0
argc=2
argv[0] = --unused
argv[1] = --start_demo_name=Physics Server
ExampleBrowserThreadFunc started
X11 functions dynamically loaded using dlopen/dlsym OK!
X11 functions dynamically loaded using dlopen/dlsym OK!
Creating context
Created GL 3.3 context
Direct GLX rendering context obtained
Making context current
GL_VENDOR=AMD
GL_RENDERER=AMD Radeon RX 6700 XT (NAVY_FLOUNDER, DRM 3.42.0, 5.15.0-89-generic, LLVM 12.0.0)
GL_VERSION=4.6 (Core Profile) Mesa 21.2.6
GL_SHADING_LANGUAGE_VERSION=4.60
pthread_getconcurrency()=0
Version = 4.6 (Core Profile) Mesa 21.2.6
Vendor = AMD
Renderer = AMD Radeon RX 6700 XT (NAVY_FLOUNDER, DRM 3.42.0, 5.15.0-89-generic, LLVM 12.0.0)
b3Printf: Selected demo: Physics Server
startThreads creating 1 threads.
starting thread 0
started thread 0
MotionThreadFunc thread started
ven = AMD
ven = AMD
Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/r_gripper_r_finger_tip_link (parent map) at time 1706547087.197074 according to authority default_authority
         at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp
Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/r_gripper_palm_link (parent map) at time 1706547087.480158 according to authority default_authority
         at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp
Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/projector_wg6802418_child_frame (parent map) at time 1706547089.689294 according to authority default_authority
         at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp
Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/l_shoulder_pan_link (parent map) at time 1706547092.019791 according to authority default_authority
         at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp
no_operation()
└── plan()
    ├── perform(ParkArmsActionPerformable)
    ├── perform(MoveTorsoActionPerformable)
    ├── perform(NavigateActionPerformable)
    │   └── perform(MoveMotion)
    ├── perform(PickUpActionPerformable)
    │   ├── perform(MoveTCPMotion)
    │   ├── perform(MoveGripperMotion)
    │   ├── perform(MoveTCPMotion)
    │   ├── perform(MoveGripperMotion)
    │   └── perform(MoveTCPMotion)
    ├── perform(ParkArmsActionPerformable)
    ├── perform(NavigateActionPerformable)
    │   └── perform(MoveMotion)
    ├── perform(PlaceActionPerformable)
    │   ├── perform(MoveTCPMotion)
    │   ├── perform(MoveGripperMotion)
    │   └── perform(MoveTCPMotion)
    └── perform(ParkArmsActionPerformable)

Next we serialize the task tree by recursively inserting from its root.

[4]:
task_tree.root.insert(session)
Inserting TaskTree into database: 100%|██████████| 20/20 [00:00<00:00, 105.04it/s]
[4]:
TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1)

We can look at our experiment (Process)MetaData to get some context on the data we just created.

[5]:
from sqlalchemy import select

print(*session.scalars(select(pycram.orm.base.ProcessMetaData)).all())
ProcessMetaData(id=1, created_at=datetime.datetime(2024, 1, 29, 16, 51, 35), created_by='dprueser', description='Tutorial for getting familiar with the ORM.', pycram_version='5e32afdb9ba57a9d6befec2c78087fee1f5e5d9b')

Lastly we can look at various table to see how the structures got logged. For example, we can get all the navigate actions that occurred.

[6]:
navigations = session.scalars(select(pycram.orm.action_designator.NavigateAction)).all()
print(*navigations, sep="\n")
NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=3, process_metadata_id=1), pose_id=4)
NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=12, process_metadata_id=1), pose_id=13)

Due to the inheritance mapped in the ORM package, we can also obtain all executed actions with just one query.

[7]:
actions = session.scalars(select(pycram.orm.action_designator.Action)).all()
print(*actions, sep="\n")
ParkArmsAction(id=1, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=1, robot_state=RobotState(id=1, torso_height=0.0, type=<ObjectType.ROBOT: 6>, pose_id=1, process_metadata_id=1), arm=<Arms.BOTH: 3>)
MoveTorsoAction(id=2, process_metadata_id=1, dtype='MoveTorsoAction', robot_state_id=2, robot_state=RobotState(id=2, torso_height=0.0, type=<ObjectType.ROBOT: 6>, pose_id=2, process_metadata_id=1), position=0.3)
NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=3, process_metadata_id=1), pose_id=4)
PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1)
ParkArmsAction(id=11, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=5, robot_state=RobotState(id=5, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=11, process_metadata_id=1), arm=<Arms.BOTH: 3>)
NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=12, process_metadata_id=1), pose_id=13)
PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2)
ParkArmsAction(id=18, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=8, robot_state=RobotState(id=8, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=20, process_metadata_id=1), arm=<Arms.BOTH: 3>)

Of course all relational algebra operators, such as filtering and joining also work in pycram.orm queries. Let’s say we need all the poses of objects, that were picked up by a robot. Since we defined a relationship between the PickUpAction table and the Object table and between the Object table and the Pose table in the ORM class schema, we can just use the join operator without any further specification:

[8]:
object_actions = (session.scalars(select(pycram.orm.base.Pose)
                  .join(pycram.orm.action_designator.PickUpAction.object)
                  .join(pycram.orm.object_designator.Object.pose))
                  .all())
print(*object_actions, sep="\n")

Pose(id=7, time=datetime.datetime(2024, 1, 29, 16, 51, 15, 804838), frame='map', position_id=7, orientation_id=7, process_metadata_id=1)

Did you notice, that for the joins we did not join the tables together in a typical sql kind of way, but rather used the relationships defined in the ORM classes and wrote joins like PickUpAction.object or Object.pose? This is because the ORM package automatically creates the joins for us, so we only have to join on the attributes that hold the relationship. This is a huge advantage over writing sql queries by hand, since we do not have to worry about the join conditions. This is a strong tool, but it is crucial to use it properly. Very important to note: The order of the joins matters! For instance, if we joined the Pose table with the Object table first, and placed the join between the PickUpAction table and the Object table second, sqlalchemy would have selected the Pose not from the join between all three tables, but rather from a join between the Pose and the Object table + from a join between the PickUpAction table and the Object table. These mistakes can lead to wrong results or even to errors (the above-mentioned example would actually lead to an error due to the Object table being accessed twice in two separate joins in the same query and therefore the column names of the Object tables would have been ambiguous and could not be used by sqlalchemy to join).

Make sure to check out the other examples of ORM querying.

If we want to filter for all successful tasks we can just add the filter operator:

[9]:
successful_tasks = session.scalars(select(pycram.orm.task.TaskTreeNode).where(pycram.orm.task.TaskTreeNode.status == "SUCCEEDED"))
print(*successful_tasks, sep="\n")
TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=3, code_id=3, code=Code(id=3, function='perform', designator_id=1, designator=ParkArmsAction(id=1, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=1, robot_state=RobotState(id=1, torso_height=0.0, type=<ObjectType.ROBOT: 6>, pose_id=1, process_metadata_id=1), arm=<Arms.BOTH: 3>), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872243), end_time=datetime.datetime(2024, 1, 29, 17, 51, 16, 378193), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=4, code_id=4, code=Code(id=4, function='perform', designator_id=2, designator=MoveTorsoAction(id=2, process_metadata_id=1, dtype='MoveTorsoAction', robot_state_id=2, robot_state=RobotState(id=2, torso_height=0.0, type=<ObjectType.ROBOT: 6>, pose_id=2, process_metadata_id=1), position=0.3), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 16, 378288), end_time=datetime.datetime(2024, 1, 29, 17, 51, 16, 881639), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 459617), end_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970219), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=6, code_id=6, code=Code(id=6, function='perform', designator_id=4, designator=MoveMotion(id=4, process_metadata_id=1, dtype='MoveMotion', pose_id=5), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 459689), end_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970208), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=5, parent=TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 459617), end_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970219), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=8, code_id=8, code=Code(id=8, function='perform', designator_id=6, designator=MoveTCPMotion(id=6, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=8), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 18, 122271), end_time=datetime.datetime(2024, 1, 29, 17, 51, 18, 631460), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=9, code_id=9, code=Code(id=9, function='perform', designator_id=7, designator=MoveGripperMotion(id=7, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 18, 631582), end_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 141918), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=10, code_id=10, code=Code(id=10, function='perform', designator_id=8, designator=MoveTCPMotion(id=8, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=9), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 273490), end_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 783950), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=11, code_id=11, code=Code(id=11, function='perform', designator_id=9, designator=MoveGripperMotion(id=9, process_metadata_id=1, dtype='MoveGripperMotion', motion='close', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 784120), end_time=datetime.datetime(2024, 1, 29, 17, 51, 20, 298210), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=12, code_id=12, code=Code(id=12, function='perform', designator_id=10, designator=MoveTCPMotion(id=10, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=10), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 20, 457629), end_time=datetime.datetime(2024, 1, 29, 17, 51, 20, 974496), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=13, code_id=13, code=Code(id=13, function='perform', designator_id=11, designator=ParkArmsAction(id=11, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=5, robot_state=RobotState(id=5, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=11, process_metadata_id=1), arm=<Arms.BOTH: 3>), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274678), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 782383), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 32, 702999), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209586), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=15, code_id=15, code=Code(id=15, function='perform', designator_id=13, designator=MoveMotion(id=13, process_metadata_id=1, dtype='MoveMotion', pose_id=14), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 32, 703060), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209577), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=14, parent=TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 32, 702999), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209586), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=17, code_id=17, code=Code(id=17, function='perform', designator_id=15, designator=MoveTCPMotion(id=15, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=18), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 210786), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 721856), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=18, code_id=18, code=Code(id=18, function='perform', designator_id=16, designator=MoveGripperMotion(id=16, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 722026), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 239587), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=19, code_id=19, code=Code(id=19, function='perform', designator_id=17, designator=MoveTCPMotion(id=17, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=19), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 241042), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751946), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)
TaskTreeNode(id=20, code_id=20, code=Code(id=20, function='perform', designator_id=18, designator=ParkArmsAction(id=18, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=8, robot_state=RobotState(id=8, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=20, process_metadata_id=1), arm=<Arms.BOTH: 3>), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 752094), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265524), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=<TaskStatus.SUCCEEDED: 2>, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=<TaskStatus.RUNNING: 1>, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)

As expected all but the root node succeeded, since the root node is still running.

Writing an extension to the ORM package is also done with ease. We need to create a new ActionDesignator class and its ORM equivalent, where we define our new table. Let’s say we want to log all the things the robot says. We will create a new ActionDesignator class called Saying and its ORM equivalent called ORMSaying.

[10]:
from sqlalchemy.orm import Mapped, mapped_column, Session
from pycram.orm.action_designator import Action
from dataclasses import dataclass


# define ORM class from pattern in every pycram.orm class
class ORMSaying(Action):

    id: Mapped[int] = mapped_column(sqlalchemy.ForeignKey(f'{Action.__tablename__}.id'), primary_key=True, init=False)
    # since we do not want to add any custom specifications to our column, we don't even need to define mapped_column, sqlalchemy does this internally.
    text: Mapped[str]

# define brand new action designator

@dataclass
class SayingActionPerformable(ActionDesignatorDescription.Action):

    text: str

    @with_tree
    def perform(self) -> None:
        print(self.text)

    def to_sql(self) -> ORMSaying:
        return ORMSaying(self.text)

    def insert(self, session: Session, *args, **kwargs) -> ORMSaying:
        action = super().insert(session)
        session.add(action)
        session.commit()
        return action

Now we got our new ActionDesignator called Saying and its ORM version. Since this class got created after all other classes got inserted into the database (in the beginning of the notebook) we have to insert it manually.

[11]:
ORMSaying.metadata.create_all(bind=engine)

Now we can create and insert a Saying action. Since this is the last part where we interact with the BulletWorld, we can also close it.

[12]:
# create a saying action and insert it
SayingActionPerformable("Patchie, Patchie; Where is my Patchie?").perform()
pycram.task.task_tree.root.insert(session)
session.commit()

world.exit()
Patchie, Patchie; Where is my Patchie?
Inserting TaskTree into database: 100%|██████████| 21/21 [00:00<00:00, 116.25it/s]

It is notable that committing the object to the session fills its primary key. Hence, there is no worries about assigning unique IDs manually. Finally, we can double-check that our object exists in the database.

[14]:
session.scalars(select(ORMSaying)).all()
[14]:
[ORMSaying(id=37, process_metadata_id=1, dtype='ORMSaying', robot_state_id=17, robot_state=RobotState(id=17, torso_height=0.3, type=<ObjectType.ROBOT: 6>, pose_id=41, process_metadata_id=1), text='Patchie, Patchie; Where is my Patchie?')]