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=1, 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 )
73 sim = SimulationManager(config)
74
75 # Build multiple environments if requested
76 if args.num_envs > 1:
77 sim.build_multiple_arenas(args.num_envs)
78
79 # Create robot configuration
80 robot = create_robot(sim)
81
82 # Initialize GPU physics if using CUDA
83 if sim.is_use_gpu_physics:
84 sim.init_gpu_physics()
85
86 # Open visualization window if not headless
87 if not args.headless:
88 sim.open_window()
89
90 # Run simulation loop
91 run_simulation(sim, robot)
92
93
94def create_robot(sim):
95 """Create and configure a robot in the simulation."""
96
97 print("Loading robot...")
98
99 # Get SR5 arm URDF path
100 sr5_urdf_path = get_data_path("Rokae/SR5/SR5.urdf")
101
102 # Get hand URDF path
103 hand_urdf_path = get_data_path(
104 "BrainCoHandRevo1/BrainCoLeftHand/BrainCoLeftHand.urdf"
105 )
106
107 # Define control parts for the robot
108 # Joint names in control_parts can be regex patterns
109 CONTROL_PARTS = {
110 "arm": [
111 "JOINT[1-6]", # Matches JOINT1, JOINT2, ..., JOINT6
112 ],
113 "hand": ["LEFT_.*"], # Matches all joints starting with L_
114 }
115
116 # Define transformation for hand attachment
117 hand_attach_xpos = np.eye(4)
118 hand_attach_xpos[:3, :3] = R.from_rotvec([90, 0, 0], degrees=True).as_matrix()
119 hand_attach_xpos[2, 3] = 0.02
120
121 cfg = RobotCfg(
122 uid="sr5_with_brainco",
123 urdf_cfg=URDFCfg(
124 components=[
125 {
126 "component_type": "arm",
127 "urdf_path": sr5_urdf_path,
128 },
129 {
130 "component_type": "hand",
131 "urdf_path": hand_urdf_path,
132 "transform": hand_attach_xpos,
133 },
134 ]
135 ),
136 control_parts=CONTROL_PARTS,
137 drive_pros=JointDrivePropertiesCfg(
138 stiffness={"JOINT[1-6]": 1e4, "LEFT_.*": 1e3},
139 damping={"JOINT[1-6]": 1e3, "LEFT_.*": 1e2},
140 ),
141 )
142
143 # Add robot to simulation
144 robot: Robot = sim.add_robot(cfg=cfg)
145
146 print(f"Robot created successfully with {robot.dof} joints")
147
148 return robot
149
150
151def run_simulation(sim: SimulationManager, robot: Robot):
152 """Run the simulation loop with robot control."""
153
154 print("Starting simulation...")
155 print("Robot will move through different poses")
156 print("Press Ctrl+C to stop")
157
158 step_count = 0
159
160 arm_joint_ids = robot.get_joint_ids("arm")
161 # Define some target joint positions for demonstration
162 arm_position1 = (
163 torch.tensor(
164 [0.0, -0.5, 0.5, -1.0, 0.5, 0.0], dtype=torch.float32, device=sim.device
165 )
166 .unsqueeze_(0)
167 .repeat(sim.num_envs, 1)
168 )
169
170 arm_position2 = (
171 torch.tensor(
172 [0.5, 0.0, -0.5, 0.5, -0.5, 0.5], dtype=torch.float32, device=sim.device
173 )
174 .unsqueeze_(0)
175 .repeat(sim.num_envs, 1)
176 )
177
178 # Get joint IDs for the hand.
179 hand_joint_ids = robot.get_joint_ids("hand")
180 # Define hand open and close positions based on joint limits.
181 hand_position_open = robot.body_data.qpos_limits[:, hand_joint_ids, 1]
182 hand_position_close = robot.body_data.qpos_limits[:, hand_joint_ids, 0]
183
184 try:
185 while True:
186 # Update physics
187 sim.update(step=1)
188
189 if step_count % 4000 == 0:
190 robot.set_qpos(qpos=arm_position1, joint_ids=arm_joint_ids)
191 print(f"Moving to arm position 1")
192
193 if step_count % 4000 == 1000:
194 robot.set_qpos(qpos=arm_position2, joint_ids=arm_joint_ids)
195 print(f"Moving to arm position 2")
196
197 if step_count % 4000 == 2000:
198 robot.set_qpos(qpos=hand_position_close, joint_ids=hand_joint_ids)
199 print(f"Closing hand")
200
201 if step_count % 4000 == 3000:
202 robot.set_qpos(qpos=hand_position_open, joint_ids=hand_joint_ids)
203 print(f"Opening hand")
204
205 step_count += 1
206
207 except KeyboardInterrupt:
208 print("Stopping simulation...")
209 finally:
210 print("Cleaning up...")
211 sim.destroy()
212
213
214if __name__ == "__main__":
215 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.