Simulating a Robot#

This tutorial shows you how to create and simulate a robot using SimulationManager. You’ll learn how to load a robot from URDF files, configure control systems, and run basic robot simulation with joint control.

The Code#

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

Code for create_robot.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"""
 18This script demonstrates how to create and simulate a robot using SimulationManager.
 19It shows how to load a robot from URDF, set up control parts, and run basic simulation.
 20"""
 21
 22import argparse
 23import numpy as np
 24import time
 25import torch
 26
 27torch.set_printoptions(precision=4, sci_mode=False)
 28
 29from scipy.spatial.transform import Rotation as R
 30
 31from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
 32from embodichain.lab.sim.objects import Robot
 33from embodichain.lab.sim.cfg import (
 34    RenderCfg,
 35    JointDrivePropertiesCfg,
 36    RobotCfg,
 37    URDFCfg,
 38)
 39from embodichain.data import get_data_path
 40from embodichain.lab.gym.utils.gym_utils import add_env_launcher_args_to_parser
 41
 42
 43def main():
 44    """Main function to demonstrate robot simulation."""
 45
 46    # Parse command line arguments
 47    parser = argparse.ArgumentParser(
 48        description="Create and simulate a robot in SimulationManager"
 49    )
 50    add_env_launcher_args_to_parser(parser)
 51    args = parser.parse_args()
 52
 53    # Initialize simulation
 54    print("Creating simulation...")
 55    config = SimulationManagerCfg(
 56        headless=True,
 57        sim_device=args.device,
 58        arena_space=3.0,
 59        render_cfg=RenderCfg(renderer=args.renderer),
 60        physics_dt=1.0 / 100.0,
 61        num_envs=args.num_envs,
 62    )
 63    sim = SimulationManager(config)
 64
 65    # Create robot configuration
 66    robot = create_robot(sim)
 67
 68    # Initialize GPU physics if using CUDA
 69    if sim.is_use_gpu_physics:
 70        sim.init_gpu_physics()
 71
 72    # Open visualization window if not headless
 73    if not args.headless:
 74        sim.open_window()
 75
 76    # Run simulation loop
 77    run_simulation(sim, robot)
 78
 79
 80def create_robot(sim):
 81    """Create and configure a robot in the simulation."""
 82
 83    print("Loading robot...")
 84
 85    # Get SR5 arm URDF path
 86    sr5_urdf_path = get_data_path("Rokae/SR5/SR5.urdf")
 87
 88    # Get hand URDF path
 89    hand_urdf_path = get_data_path(
 90        "BrainCoHandRevo1/BrainCoLeftHand/BrainCoLeftHand.urdf"
 91    )
 92
 93    # Define control parts for the robot
 94    # Joint names in control_parts can be regex patterns
 95    CONTROL_PARTS = {
 96        "arm": [
 97            "JOINT[1-6]",  # Matches JOINT1, JOINT2, ..., JOINT6
 98        ],
 99        "hand": ["LEFT_.*"],  # Matches all joints starting with L_
100    }
101
102    # Define transformation for hand attachment
103    hand_attach_xpos = np.eye(4)
104    hand_attach_xpos[:3, :3] = R.from_rotvec([90, 0, 0], degrees=True).as_matrix()
105    hand_attach_xpos[2, 3] = 0.02
106
107    cfg = RobotCfg(
108        uid="sr5_with_brainco",
109        urdf_cfg=URDFCfg(
110            components=[
111                {
112                    "component_type": "arm",
113                    "urdf_path": sr5_urdf_path,
114                },
115                {
116                    "component_type": "hand",
117                    "urdf_path": hand_urdf_path,
118                    "transform": hand_attach_xpos,
119                },
120            ]
121        ),
122        control_parts=CONTROL_PARTS,
123        drive_pros=JointDrivePropertiesCfg(
124            stiffness={"JOINT[1-6]": 1e4, "LEFT_.*": 1e3},
125            damping={"JOINT[1-6]": 1e3, "LEFT_.*": 1e2},
126        ),
127    )
128
129    # Add robot to simulation
130    robot: Robot = sim.add_robot(cfg=cfg)
131
132    print(f"Robot created successfully with {robot.dof} joints")
133
134    return robot
135
136
137def run_simulation(sim: SimulationManager, robot: Robot):
138    """Run the simulation loop with robot control."""
139
140    print("Starting simulation...")
141    print("Robot will move through different poses")
142    print("Press Ctrl+C to stop")
143
144    step_count = 0
145
146    arm_joint_ids = robot.get_joint_ids("arm")
147    # Define some target joint positions for demonstration
148    arm_position1 = (
149        torch.tensor(
150            [0.0, -0.5, 0.5, -1.0, 0.5, 0.0], dtype=torch.float32, device=sim.device
151        )
152        .unsqueeze_(0)
153        .repeat(sim.num_envs, 1)
154    )
155
156    arm_position2 = (
157        torch.tensor(
158            [0.5, 0.0, -0.5, 0.5, -0.5, 0.5], dtype=torch.float32, device=sim.device
159        )
160        .unsqueeze_(0)
161        .repeat(sim.num_envs, 1)
162    )
163
164    # Get joint IDs for the hand.
165    hand_joint_ids = robot.get_joint_ids("hand")
166    # Define hand open and close positions based on joint limits.
167    hand_position_open = robot.body_data.qpos_limits[:, hand_joint_ids, 1]
168    hand_position_close = robot.body_data.qpos_limits[:, hand_joint_ids, 0]
169
170    try:
171        while True:
172            # Update physics
173            sim.update(step=1)
174
175            if step_count % 4000 == 0:
176                robot.set_qpos(qpos=arm_position1, joint_ids=arm_joint_ids)
177                print(f"Moving to arm position 1")
178
179            if step_count % 4000 == 1000:
180                robot.set_qpos(qpos=arm_position2, joint_ids=arm_joint_ids)
181                print(f"Moving to arm position 2")
182
183            if step_count % 4000 == 2000:
184                robot.set_qpos(qpos=hand_position_close, joint_ids=hand_joint_ids)
185                print(f"Closing hand")
186
187            if step_count % 4000 == 3000:
188                robot.set_qpos(qpos=hand_position_open, joint_ids=hand_joint_ids)
189                print(f"Opening hand")
190
191            step_count += 1
192
193    except KeyboardInterrupt:
194        print("Stopping simulation...")
195    finally:
196        print("Cleaning up...")
197        sim.destroy()
198
199
200if __name__ == "__main__":
201    main()

The Code Explained#

Similar to the previous tutorial on creating a simulation scene, we use the SimulationManager class to set up the simulation environment. If you haven’t read that tutorial yet, please refer to Creating a simulation scene first.

Loading Robot URDF#

SimulationManager supports loading robots from URDF (Unified Robot Description Format) files. You can load either a single URDF file or compose multiple URDF components into a complete robot system.

For a simple two-component robot (arm + hand):

    sr5_urdf_path = get_data_path("Rokae/SR5/SR5.urdf")

    # Get hand URDF path
    hand_urdf_path = get_data_path(
        "BrainCoHandRevo1/BrainCoLeftHand/BrainCoLeftHand.urdf"
    )

    # Define control parts for the robot
    # Joint names in control_parts can be regex patterns
    CONTROL_PARTS = {
        "arm": [
            "JOINT[1-6]",  # Matches JOINT1, JOINT2, ..., JOINT6
        ],
        "hand": ["LEFT_.*"],  # Matches all joints starting with L_
    }

    # Define transformation for hand attachment
    hand_attach_xpos = np.eye(4)
    hand_attach_xpos[:3, :3] = R.from_rotvec([90, 0, 0], degrees=True).as_matrix()
    hand_attach_xpos[2, 3] = 0.02

    cfg = RobotCfg(
        uid="sr5_with_brainco",
        urdf_cfg=URDFCfg(
            components=[
                {
                    "component_type": "arm",
                    "urdf_path": sr5_urdf_path,
                },
                {
                    "component_type": "hand",
                    "urdf_path": hand_urdf_path,
                    "transform": hand_attach_xpos,
                },
            ]
        ),
        control_parts=CONTROL_PARTS,
        drive_pros=JointDrivePropertiesCfg(
            stiffness={"JOINT[1-6]": 1e4, "LEFT_.*": 1e3},
            damping={"JOINT[1-6]": 1e3, "LEFT_.*": 1e2},
        ),
    )

    # Add robot to simulation
    robot: Robot = sim.add_robot(cfg=cfg)

The cfg.URDFCfg allows you to compose multiple URDF files with specific transformations, enabling complex robot assemblies.

Configuring Control Parts#

Control parts define how the robot’s joints are grouped for control purposes. This is useful for organizing complex robots with multiple subsystems.

    # Define control parts for the robot
    # Joint names in control_parts can be regex patterns
    CONTROL_PARTS = {
        "arm": [
            "JOINT[1-6]",  # Matches JOINT1, JOINT2, ..., JOINT6
        ],
        "hand": ["LEFT_.*"],  # Matches all joints starting with L_
    }

Joint names in control parts can use regex patterns for flexible matching. For example:

  • "JOINT[1-6]" matches JOINT1, JOINT2, …, JOINT6

  • "L_.*" matches all joints starting with “L_”

Setting Drive Properties#

Drive properties control how the robot’s joints behave during simulation, including stiffness, damping, and force limits.

        drive_pros=JointDrivePropertiesCfg(
            stiffness={"JOINT[1-6]": 1e4, "LEFT_.*": 1e3},
            damping={"JOINT[1-6]": 1e3, "LEFT_.*": 1e2},
        ),

You can set different stiffness values for different joint groups using regex patterns. More details on drive properties can be found in cfg.JointDrivePropertiesCfg.

For more robot configuration options, refer to cfg.RobotCfg.

Robot Control#

For the basic control of robot joints, you can set position targets using objects.Robot.set_qpos(). The control action should be created as a torch.Tensor with shape (num_envs, num_joints), where num_joints is the total number of joints in the robot or the number of joints in a specific control part.

  • If you can control all joints, use:

    robot.set_qpos(qpos=target_positions)
    
  • If you want to control a subset of joints, specify the joint IDs:

    robot.set_qpos(qpos=target_positions, joint_ids=subset_joint_ids)
    

Getting Robot State#

You can query the robot’s current joint positions and velocities via objects.Robot.get_qpos() and objects.Robot.get_qvel(). For more robot API details, see objects.Robot.

The Code Execution#

To run the robot simulation script:

cd /root/sources/embodichain
python scripts/tutorials/sim/create_robot.py

You can customize the simulation with various command-line options:

# Run with GPU physics
python scripts/tutorials/sim/create_robot.py --device cuda

# Run multiple environments
python scripts/tutorials/sim/create_robot.py --num_envs 4

# Run in headless mode
python scripts/tutorials/sim/create_robot.py --headless

# Enable ray tracing rendering
python scripts/tutorials/sim/create_robot.py --renderer

The simulation will show the robot moving through different poses, demonstrating basic joint control capabilities.

Key Features Demonstrated#

This tutorial demonstrates several key features of robot simulation in SimulationManager:

  1. URDF Loading: Both single-file and multi-component robot loading

  2. Control Parts: Organizing joints into logical control groups

  3. Drive Properties: Configuring joint stiffness and control behavior

  4. Joint Control: Setting position targets and reading joint states

  5. Multi-Environment: Running multiple robot instances in parallel

Next Steps#

After mastering basic robot simulation, you can explore:

  • End-effector control and inverse kinematics

  • Sensor integration (cameras, force sensors)

  • Robot-object interaction scenarios

This tutorial provides the foundation for creating sophisticated robotic simulation scenarios with SimulationManager.