Atomic Actions#

EmbodiChain’s atomic action layer provides a high-level, composable interface for common manipulation primitives such as move, pick up, and place. Each action encapsulates the full planning pipeline — grasp-pose estimation, IK, trajectory generation, and gripper interpolation — behind a single execute() call, making it straightforward to chain multiple actions together into complex robot behaviours.

Key Features#

  • Semantic-aware execution — actions accept either a raw pose tensor or an ObjectSemantics descriptor that bundles affordance data (grasp poses, interaction points) with the simulation entity.

  • Three built-in primitivesMoveAction, PickUpAction, and PlaceAction cover the most common tabletop manipulation workflows out of the box. See the supported_atomic_actions table for configs and target types.

  • Extensible registry — custom actions can be registered globally with register_action and discovered by the engine at runtime.

  • Engine orchestrationAtomicActionEngine sequences multiple actions, threads start_qpos from one action to the next, and returns a single concatenated trajectory ready to replay in the simulator.

For the full design overview, architecture diagram, and extension guide see Atomic Actions.

The Code#

The tutorial corresponds to the atomic_actions.py script in the scripts/tutorials/sim directory.

Code for atomic_actions.py
  1# ----------------------------------------------------------------------------
  2# Copyright (c) 2021-2026 DexForce Technology Co., Ltd.
  3#
  4# Licensed under the Apache License, Version 2.0 (the "License");
  5# you may not use this file except in compliance with the License.
  6# You may obtain a copy of the License at
  7#
  8#     http://www.apache.org/licenses/LICENSE-2.0
  9#
 10# Unless required by applicable law or agreed to in writing, software
 11# distributed under the License is distributed on an "AS IS" BASIS,
 12# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 13# See the License for the specific language governing permissions and
 14# limitations under the License.
 15# ----------------------------------------------------------------------------
 16
 17"""
 18Tutorial: Atomic Actions for Robot Motion Generation
 19=====================================================
 20
 21This script shows how to use the atomic action system to plan and execute
 22a pick-and-place task with a robot arm.
 23
 24Key concepts covered:
 25  1. Setting up a MotionGenerator and AtomicActionEngine
 26  2. Describing what to pick using ObjectSemantics and AntipodalAffordance
 27  3. Running a pick → place → move sequence with execute_static()
 28
 29Run with:
 30    python atomic_actions.py [--num_envs N] [--renderer hybrid|fast-rt|rt]
 31"""
 32
 33import argparse
 34import numpy as np
 35import time
 36import torch
 37
 38from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
 39from embodichain.lab.sim.objects import Robot, RigidObject
 40from embodichain.lab.sim.shapes import MeshCfg
 41from embodichain.lab.sim.solvers import PytorchSolverCfg
 42from embodichain.data import get_data_path
 43from embodichain.lab.gym.utils.gym_utils import add_env_launcher_args_to_parser
 44from embodichain.lab.sim.cfg import (
 45    JointDrivePropertiesCfg,
 46    RenderCfg,
 47    RobotCfg,
 48    RigidObjectCfg,
 49    RigidBodyAttributesCfg,
 50    LightCfg,
 51    URDFCfg,
 52)
 53from embodichain.lab.sim.planners import MotionGenerator, MotionGenCfg, ToppraPlannerCfg
 54from embodichain.toolkits.graspkit.pg_grasp.gripper_collision_checker import (
 55    GripperCollisionCfg,
 56)
 57from embodichain.toolkits.graspkit.pg_grasp.antipodal_generator import (
 58    GraspGenerator,
 59    GraspGeneratorCfg,
 60    AntipodalSamplerCfg,
 61)
 62
 63# Import everything from the public atomic_actions API
 64from embodichain.lab.sim.atomic_actions import (
 65    AtomicActionEngine,
 66    ObjectSemantics,
 67    AntipodalAffordance,
 68    PickUpActionCfg,
 69    PlaceActionCfg,
 70    MoveActionCfg,
 71)
 72
 73
 74def parse_arguments():
 75    """
 76    Parse command-line arguments to configure the simulation.
 77
 78    Returns:
 79        argparse.Namespace: Parsed arguments including number of environments, device, and rendering options.
 80    """
 81    parser = argparse.ArgumentParser(
 82        description="Create and simulate a robot in SimulationManager"
 83    )
 84    add_env_launcher_args_to_parser(parser)
 85    return parser.parse_args()
 86
 87
 88def initialize_simulation(args):
 89    """
 90    Initialize the simulation environment based on the provided arguments.
 91
 92    Args:
 93        args (argparse.Namespace): Parsed command-line arguments.
 94
 95    Returns:
 96        SimulationManager: Configured simulation manager instance.
 97    """
 98    sim_cfg = SimulationManagerCfg(
 99        width=1920,
100        height=1080,
101        headless=True,
102        sim_device="cuda",
103        physics_dt=1.0 / 100.0,
104        num_envs=args.num_envs,
105        render_cfg=RenderCfg(renderer=args.renderer),
106    )
107    sim = SimulationManager(sim_cfg)
108
109    light = sim.add_light(
110        cfg=LightCfg(uid="main_light", intensity=50.0, init_pos=(0, 0, 2.0))
111    )
112
113    return sim
114
115
116def create_robot(sim: SimulationManager, position=[0.0, 0.0, 0.0]):
117    """
118    Create and configure a robot with an arm and a dexterous hand in the simulation.
119
120    Args:
121        sim (SimulationManager): The simulation manager instance.
122
123    Returns:
124        Robot: The configured robot instance added to the simulation.
125    """
126    # Retrieve URDF paths for the robot arm and hand
127    ur10_urdf_path = get_data_path("UniversalRobots/UR10/UR10.urdf")
128    gripper_urdf_path = get_data_path("DH_PGC_140_50_M/DH_PGC_140_50_M.urdf")
129    # Configure the robot with its components and control properties
130    cfg = RobotCfg(
131        uid="UR10",
132        urdf_cfg=URDFCfg(
133            components=[
134                {"component_type": "arm", "urdf_path": ur10_urdf_path},
135                {"component_type": "hand", "urdf_path": gripper_urdf_path},
136            ]
137        ),
138        drive_pros=JointDrivePropertiesCfg(
139            stiffness={"JOINT[0-9]": 1e4, "FINGER[1-2]": 1e2},
140            damping={"JOINT[0-9]": 1e3, "FINGER[1-2]": 1e1},
141            max_effort={"JOINT[0-9]": 1e5, "FINGER[1-2]": 1e3},
142            drive_type="force",
143        ),
144        control_parts={
145            "arm": ["JOINT[0-9]"],
146            "hand": ["FINGER[1-2]"],
147        },
148        solver_cfg={
149            "arm": PytorchSolverCfg(
150                end_link_name="ee_link",
151                root_link_name="base_link",
152                tcp=[
153                    [0.0, 1.0, 0.0, 0.0],
154                    [-1.0, 0.0, 0.0, 0.0],
155                    [0.0, 0.0, 1.0, 0.12],
156                    [0.0, 0.0, 0.0, 1.0],
157                ],
158            )
159        },
160        init_qpos=[0.0, -np.pi / 2, -np.pi / 2, np.pi / 2, -np.pi / 2, 0.0, 0.0, 0.0],
161        init_pos=position,
162    )
163    return sim.add_robot(cfg=cfg)
164
165
166def create_mug(sim: SimulationManager) -> RigidObject:
167    mug_cfg = RigidObjectCfg(
168        uid="mug",
169        shape=MeshCfg(
170            fpath=get_data_path("CoffeeCup/cup.ply"),
171        ),
172        attrs=RigidBodyAttributesCfg(
173            mass=0.01,
174            dynamic_friction=0.97,
175            static_friction=0.99,
176        ),
177        max_convex_hull_num=16,
178        init_pos=[0.55, 0.0, 0.01],
179        init_rot=[0.0, 0.0, -90],
180        body_scale=(4, 4, 4),
181    )
182    mug = sim.add_rigid_object(cfg=mug_cfg)
183    return mug
184
185
186def main():
187    """Pick up a mug and place it at a new location using atomic actions."""
188    args = parse_arguments()
189
190    # ------------------------------------------------------------------ #
191    # Step 1: Set up simulation, robot, and object                        #
192    # ------------------------------------------------------------------ #
193    sim: SimulationManager = initialize_simulation(args)
194    robot = create_robot(sim)
195    mug = create_mug(sim)
196
197    # ------------------------------------------------------------------ #
198    # Step 2: Create a MotionGenerator for the robot                      #
199    # MotionGenerator handles trajectory planning (IK + TOPPRA smoothing) #
200    # ------------------------------------------------------------------ #
201    motion_gen = MotionGenerator(
202        cfg=MotionGenCfg(planner_cfg=ToppraPlannerCfg(robot_uid=robot.uid))
203    )
204
205    # ------------------------------------------------------------------ #
206    # Step 3: Configure the three atomic actions                          #
207    #                                                                     #
208    #  PickUpAction  — approach → close gripper → lift                   #
209    #  PlaceAction   — lower → open gripper → retract                    #
210    #  MoveAction    — free-space move to a target EEF pose               #
211    # ------------------------------------------------------------------ #
212    # Gripper joint values for this robot (DH_PGC_140):
213    #   open  = [0.00, 0.00]   (fully open)
214    #   close = [0.025, 0.025] (grasping width)
215    hand_open = torch.tensor([0.00, 0.00], dtype=torch.float32, device=sim.device)
216    hand_close = torch.tensor([0.025, 0.025], dtype=torch.float32, device=sim.device)
217
218    pickup_cfg = PickUpActionCfg(
219        control_part="arm",
220        hand_control_part="hand",
221        hand_open_qpos=hand_open,
222        hand_close_qpos=hand_close,
223        # Approach the object from directly above (negative world-Z)
224        approach_direction=torch.tensor(
225            [0.0, 0.0, -1.0], dtype=torch.float32, device=sim.device
226        ),
227        pre_grasp_distance=0.15,  # hover 15 cm above before descending
228        lift_height=0.15,  # lift 15 cm after grasping
229    )
230
231    place_cfg = PlaceActionCfg(
232        control_part="arm",
233        hand_control_part="hand",
234        hand_open_qpos=hand_open,
235        hand_close_qpos=hand_close,
236        lift_height=0.15,
237    )
238
239    move_cfg = MoveActionCfg(
240        control_part="arm",
241    )
242
243    # ------------------------------------------------------------------ #
244    # Step 4: Build the AtomicActionEngine                                #
245    #                                                                     #
246    # actions_cfg_list defines the ORDER of actions that execute_static() #
247    # will run. Each entry is matched positionally to target_list.        #
248    # ------------------------------------------------------------------ #
249    atomic_engine = AtomicActionEngine(
250        motion_generator=motion_gen,
251        actions_cfg_list=[pickup_cfg, place_cfg, move_cfg],
252    )
253
254    sim.init_gpu_physics()
255    if not args.headless:
256        sim.open_window()
257
258    # ------------------------------------------------------------------ #
259    # Step 5: Describe the mug with ObjectSemantics                       #
260    #                                                                     #
261    # ObjectSemantics bundles together:                                   #
262    #   - geometry (mesh vertices/triangles for grasp annotation)         #
263    #   - affordance (how to grasp the object — here antipodal grasps)   #
264    #   - entity reference (so the action can read the live object pose)  #
265    # ------------------------------------------------------------------ #
266    mug_grasp_affordance = AntipodalAffordance(
267        object_label="mug",
268        force_reannotate=False,
269        custom_config={
270            "gripper_collision_cfg": GripperCollisionCfg(
271                max_open_length=0.088, finger_length=0.078, point_sample_dense=0.012
272            ),
273            "generator_cfg": GraspGeneratorCfg(
274                viser_port=11801,
275                antipodal_sampler_cfg=AntipodalSamplerCfg(
276                    n_sample=20000, max_length=0.088, min_length=0.003
277                ),
278            ),
279        },
280    )
281    mug_semantics = ObjectSemantics(
282        label="mug",
283        geometry={
284            "mesh_vertices": mug.get_vertices(env_ids=[0], scale=True)[0],
285            "mesh_triangles": mug.get_triangles(env_ids=[0])[0],
286        },
287        affordance=mug_grasp_affordance,
288        entity=mug,  # needed so PickUpAction can read the mug's live pose
289    )
290
291    # ------------------------------------------------------------------ #
292    # Step 6: Define target poses for place and final rest                #
293    #                                                                     #
294    # Poses are 4×4 homogeneous transforms (rotation | translation).     #
295    # For PickUpAction the target is mug_semantics — the action computes  #
296    # the grasp pose automatically from the affordance.                   #
297    # ------------------------------------------------------------------ #
298    # Place the mug 20 cm to the left and 40 cm forward from its pickup pose
299    place_xpos = torch.tensor(
300        [
301            [-0.0539, -0.9985, -0.0022, 0.2489],
302            [-0.9977, 0.0540, -0.0401, 0.3970],
303            [0.0401, 0.0000, -0.9992, 0.2400],
304            [0.0000, 0.0000, 0.0000, 1.0000],
305        ],
306        dtype=torch.float32,
307        device=sim.device,
308    )
309
310    # Move the arm to a safe resting pose after placing
311    rest_xpos = torch.tensor(
312        [
313            [-0.0539, -0.9985, -0.0022, 0.5000],
314            [-0.9977, 0.0540, -0.0401, 0.0000],
315            [0.0401, 0.0000, -0.9992, 0.5000],
316            [0.0000, 0.0000, 0.0000, 1.0000],
317        ],
318        dtype=torch.float32,
319        device=sim.device,
320    )
321
322    # ------------------------------------------------------------------ #
323    # Step 7: Plan and execute the full sequence                          #
324    #                                                                     #
325    # execute_static() plans all three actions in order and returns a     #
326    # single concatenated joint trajectory (n_envs, n_waypoints, dof).   #
327    # We then replay it frame-by-frame in the simulator.                 #
328    # ------------------------------------------------------------------ #
329    print("Planning pick → place → move trajectory...")
330    is_success, traj = atomic_engine.execute_static(
331        target_list=[mug_semantics, place_xpos, rest_xpos]
332    )
333
334    if not is_success:
335        print("Planning failed. Check that the target poses are reachable.")
336        return
337
338    print(f"Success! Replaying {traj.shape[1]} waypoints...")
339    for i in range(traj.shape[1]):
340        robot.set_qpos(traj[:, i])
341        sim.update(step=4)
342        time.sleep(1e-2)
343
344    input("Press Enter to exit...")
345
346
347if __name__ == "__main__":
348    main()

Typical Usage#

Setting up the engine#

import torch
from embodichain.lab.sim.planners import MotionGenerator, MotionGenCfg
from embodichain.lab.sim.atomic_actions import (
    AtomicActionEngine,
    PickUpActionCfg,
    PlaceActionCfg,
    MoveActionCfg,
)

motion_gen = MotionGenerator(cfg=MotionGenCfg(...))

hand_open  = torch.tensor([0.00,  0.00],  dtype=torch.float32, device=device)
hand_close = torch.tensor([0.025, 0.025], dtype=torch.float32, device=device)

pickup_cfg = PickUpActionCfg(
    hand_open_qpos=hand_open,
    hand_close_qpos=hand_close,
    control_part="arm",
    hand_control_part="hand",
    approach_direction=torch.tensor([0.0, 0.0, -1.0], dtype=torch.float32, device=device),
    pre_grasp_distance=0.15,
    lift_height=0.15,
)
place_cfg = PlaceActionCfg(
    hand_open_qpos=hand_open,
    hand_close_qpos=hand_close,
    control_part="arm",
    hand_control_part="hand",
    lift_height=0.15,
)
move_cfg = MoveActionCfg(control_part="arm")

engine = AtomicActionEngine(
    motion_generator=motion_gen,
    actions_cfg_list=[pickup_cfg, place_cfg, move_cfg],
)

Defining object semantics#

from embodichain.lab.sim.atomic_actions import (
    ObjectSemantics,
    AntipodalAffordance,
)
from embodichain.toolkits.graspkit.pg_grasp import GraspGeneratorCfg, AntipodalSamplerCfg
from embodichain.toolkits.graspkit.pg_grasp.gripper_collision_checker import GripperCollisionCfg

affordance = AntipodalAffordance(
    object_label="mug",
    force_reannotate=False,
    custom_config={
        "gripper_collision_cfg": GripperCollisionCfg(
            max_open_length=0.088, finger_length=0.078, point_sample_dense=0.012
        ),
        "generator_cfg": GraspGeneratorCfg(
            antipodal_sampler_cfg=AntipodalSamplerCfg(
                n_sample=20000, max_length=0.088, min_length=0.003
            )
        ),
    },
)

semantics = ObjectSemantics(
    label="mug",
    geometry={
        "mesh_vertices": mug.get_vertices(env_ids=[0], scale=True)[0],
        "mesh_triangles": mug.get_triangles(env_ids=[0])[0],
    },
    affordance=affordance,
    entity=mug,   # required so the action can query the live object pose
)

Executing a pick-place-move sequence#

place_xpos = ...  # torch.Tensor [4, 4] — target placement pose
rest_xpos  = ...  # torch.Tensor [4, 4] — resting pose after placing

is_success, trajectory = engine.execute_static(
    target_list=[semantics, place_xpos, rest_xpos]
)
# trajectory: [n_envs, n_waypoints, robot_dof]

for i in range(trajectory.shape[1]):
    robot.set_qpos(trajectory[:, i])
    sim.update(step=4)

Registering custom actions#

from embodichain.lab.sim.atomic_actions import AtomicAction, ActionCfg, register_action

class PushAction(AtomicAction):
    def execute(self, target, start_qpos=None, **kwargs):
        # ... your planning logic ...
        return is_success, trajectory, joint_ids

    def validate(self, target, start_qpos=None, **kwargs):
        return True   # quick feasibility check

register_action("push", PushAction)

Notes & Best Practices#

  • PickUpAction expects an AntipodalAffordance with valid mesh data (mesh_vertices / mesh_triangles) so the grasp generator can annotate the object. Set force_reannotate=False (the default) to reuse cached annotations across episodes.

  • ObjectSemantics.entity must be set when using semantic targets so the action can read the object’s current world pose at planning time.

  • For static (non-physics) playback, iterate over trajectory[:, i] and call robot.set_qpos directly; for physics-enabled playback, feed waypoints through your controller or gym wrapper instead.

  • To add a new action type, see Atomic Actions.