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-2025 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 JointDrivePropertiesCfg,
35 RobotCfg,
36 URDFCfg,
37)
38from embodichain.data import get_data_path
39
40
41def main():
42 """Main function to demonstrate robot simulation."""
43
44 # Parse command line arguments
45 parser = argparse.ArgumentParser(
46 description="Create and simulate a robot in SimulationManager"
47 )
48 parser.add_argument(
49 "--num_envs", type=int, default=4, help="Number of environments to simulate"
50 )
51 parser.add_argument(
52 "--device",
53 type=str,
54 default="cpu",
55 choices=["cpu", "cuda"],
56 help="Device to run simulation on",
57 )
58 parser.add_argument("--headless", action="store_true", help="Run in headless mode")
59 parser.add_argument(
60 "--enable_rt", action="store_true", help="Enable ray tracing rendering"
61 )
62 args = parser.parse_args()
63
64 # Initialize simulation
65 print("Creating simulation...")
66 config = SimulationManagerCfg(
67 headless=True,
68 sim_device=args.device,
69 arena_space=3.0,
70 enable_rt=args.enable_rt,
71 physics_dt=1.0 / 100.0,
72 num_envs=args.num_envs,
73 )
74 sim = SimulationManager(config)
75
76 # Create robot configuration
77 robot = create_robot(sim)
78
79 # Initialize GPU physics if using CUDA
80 if sim.is_use_gpu_physics:
81 sim.init_gpu_physics()
82
83 # Open visualization window if not headless
84 if not args.headless:
85 sim.open_window()
86
87 # Run simulation loop
88 run_simulation(sim, robot)
89
90
91def create_robot(sim):
92 """Create and configure a robot in the simulation."""
93
94 print("Loading robot...")
95
96 # Get SR5 arm URDF path
97 sr5_urdf_path = get_data_path("Rokae/SR5/SR5.urdf")
98
99 # Get hand URDF path
100 hand_urdf_path = get_data_path(
101 "BrainCoHandRevo1/BrainCoLeftHand/BrainCoLeftHand.urdf"
102 )
103
104 # Define control parts for the robot
105 # Joint names in control_parts can be regex patterns
106 CONTROL_PARTS = {
107 "arm": [
108 "JOINT[1-6]", # Matches JOINT1, JOINT2, ..., JOINT6
109 ],
110 "hand": ["LEFT_.*"], # Matches all joints starting with L_
111 }
112
113 # Define transformation for hand attachment
114 hand_attach_xpos = np.eye(4)
115 hand_attach_xpos[:3, :3] = R.from_rotvec([90, 0, 0], degrees=True).as_matrix()
116 hand_attach_xpos[2, 3] = 0.02
117
118 cfg = RobotCfg(
119 uid="sr5_with_brainco",
120 urdf_cfg=URDFCfg(
121 components=[
122 {
123 "component_type": "arm",
124 "urdf_path": sr5_urdf_path,
125 },
126 {
127 "component_type": "hand",
128 "urdf_path": hand_urdf_path,
129 "transform": hand_attach_xpos,
130 },
131 ]
132 ),
133 control_parts=CONTROL_PARTS,
134 drive_pros=JointDrivePropertiesCfg(
135 stiffness={"JOINT[1-6]": 1e4, "LEFT_.*": 1e3},
136 damping={"JOINT[1-6]": 1e3, "LEFT_.*": 1e2},
137 ),
138 )
139
140 # Add robot to simulation
141 robot: Robot = sim.add_robot(cfg=cfg)
142
143 print(f"Robot created successfully with {robot.dof} joints")
144
145 return robot
146
147
148def run_simulation(sim: SimulationManager, robot: Robot):
149 """Run the simulation loop with robot control."""
150
151 print("Starting simulation...")
152 print("Robot will move through different poses")
153 print("Press Ctrl+C to stop")
154
155 step_count = 0
156
157 arm_joint_ids = robot.get_joint_ids("arm")
158 # Define some target joint positions for demonstration
159 arm_position1 = (
160 torch.tensor(
161 [0.0, -0.5, 0.5, -1.0, 0.5, 0.0], dtype=torch.float32, device=sim.device
162 )
163 .unsqueeze_(0)
164 .repeat(sim.num_envs, 1)
165 )
166
167 arm_position2 = (
168 torch.tensor(
169 [0.5, 0.0, -0.5, 0.5, -0.5, 0.5], dtype=torch.float32, device=sim.device
170 )
171 .unsqueeze_(0)
172 .repeat(sim.num_envs, 1)
173 )
174
175 # Get joint IDs for the hand.
176 hand_joint_ids = robot.get_joint_ids("hand")
177 # Define hand open and close positions based on joint limits.
178 hand_position_open = robot.body_data.qpos_limits[:, hand_joint_ids, 1]
179 hand_position_close = robot.body_data.qpos_limits[:, hand_joint_ids, 0]
180
181 try:
182 while True:
183 # Update physics
184 sim.update(step=1)
185
186 if step_count % 4000 == 0:
187 robot.set_qpos(qpos=arm_position1, joint_ids=arm_joint_ids)
188 print(f"Moving to arm position 1")
189
190 if step_count % 4000 == 1000:
191 robot.set_qpos(qpos=arm_position2, joint_ids=arm_joint_ids)
192 print(f"Moving to arm position 2")
193
194 if step_count % 4000 == 2000:
195 robot.set_qpos(qpos=hand_position_close, joint_ids=hand_joint_ids)
196 print(f"Closing hand")
197
198 if step_count % 4000 == 3000:
199 robot.set_qpos(qpos=hand_position_open, joint_ids=hand_joint_ids)
200 print(f"Opening hand")
201
202 step_count += 1
203
204 except KeyboardInterrupt:
205 print("Stopping simulation...")
206 finally:
207 print("Cleaning up...")
208 sim.destroy()
209
210
211if __name__ == "__main__":
212 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 --enable_rt
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:
URDF Loading: Both single-file and multi-component robot loading
Control Parts: Organizing joints into logical control groups
Drive Properties: Configuring joint stiffness and control behavior
Joint Control: Setting position targets and reading joint states
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.