Adding a New Robot#
This tutorial guides you through adding a new robot to EmbodiChain. You’ll learn the file structure, key components, and patterns used for robot definitions.
EmbodiChain supports two approaches for defining robots:
Single-file approach: For simpler robots (like
CobotMagic)Package approach: For complex robots with multiple variants (like
DexforceW1)
Choose the approach based on your robot’s complexity.
—
Prerequisites#
Before adding a new robot, ensure you have:
URDF file(s) for your robot
Robot’s kinematic parameters (DH parameters or joint limits)
Understanding of your robot’s joint structure and control parts
—
Approach 1: Single-File Robot (Simple Robots)#
Use this approach for robots with a single variant and straightforward configuration.
File: embodichain/lab/sim/robots/my_robot.py
Complete Example: CobotMagic-style Robot
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
17from __future__ import annotations
18
19import torch
20import numpy as np
21
22from typing import Dict, List, Any, Union
23
24from embodichain.lab.sim.cfg import (
25 RobotCfg,
26 URDFCfg,
27 JointDrivePropertiesCfg,
28 RigidBodyAttributesCfg,
29)
30from embodichain.lab.sim.solvers import SolverCfg, OPWSolverCfg
31from embodichain.lab.sim.utility.cfg_utils import merge_robot_cfg
32from embodichain.data import get_data_path
33from embodichain.utils import configclass
34from embodichain.utils import logger
35
36
37@configclass
38class CobotMagicCfg(RobotCfg):
39 urdf_cfg: URDFCfg = None
40 control_parts: Dict[str, List[str]] | None = None
41 solver_cfg: Dict[str, "SolverCfg"] | None = None
42
43 @classmethod
44 def from_dict(cls, init_dict: Dict[str, Union[str, float, int]]) -> CobotMagicCfg:
45
46 cfg = cls()
47 default_cfgs = cls()._build_default_cfgs()
48 for key, value in default_cfgs.items():
49 setattr(cfg, key, value)
50
51 cfg = merge_robot_cfg(cfg, init_dict)
52
53 return cfg
54
55 @staticmethod
56 def _build_default_cfgs() -> Dict[str, Any]:
57 arm_urdf = get_data_path("CobotMagicArm/CobotMagicWithGripperV100.urdf")
58 left_arm_xpos = np.array(
59 [
60 [1.0, 0.0, 0.0, 0.233],
61 [0.0, 1.0, 0.0, 0.300],
62 [0.0, 0.0, 1.0, 0.000],
63 [0.0, 0.0, 0.0, 1.000],
64 ]
65 )
66 right_arm_xpos = np.array(
67 [
68 [1.0, 0.0, 0.0, 0.233],
69 [0.0, 1.0, 0.0, -0.300],
70 [0.0, 0.0, 1.0, 0.000],
71 [0.0, 0.0, 0.0, 1.000],
72 ]
73 )
74 urdf_cfg = URDFCfg(
75 components=[
76 {
77 "component_type": "left_arm",
78 "urdf_path": arm_urdf,
79 "transform": left_arm_xpos,
80 },
81 {
82 "component_type": "right_arm",
83 "urdf_path": arm_urdf,
84 "transform": right_arm_xpos,
85 },
86 ]
87 )
88 return {
89 "uid": "CobotMagic",
90 "urdf_cfg": urdf_cfg,
91 "control_parts": {
92 "left_arm": [
93 "LEFT_JOINT1",
94 "LEFT_JOINT2",
95 "LEFT_JOINT3",
96 "LEFT_JOINT4",
97 "LEFT_JOINT5",
98 "LEFT_JOINT6",
99 ],
100 "left_eef": ["LEFT_JOINT7", "LEFT_JOINT8"],
101 "right_arm": [
102 "RIGHT_JOINT1",
103 "RIGHT_JOINT2",
104 "RIGHT_JOINT3",
105 "RIGHT_JOINT4",
106 "RIGHT_JOINT5",
107 "RIGHT_JOINT6",
108 ],
109 "right_eef": ["RIGHT_JOINT7", "RIGHT_JOINT8"],
110 },
111 "solver_cfg": {
112 "left_arm": OPWSolverCfg(
113 end_link_name="left_link6",
114 root_link_name="left_arm_base",
115 tcp=np.array(
116 [[-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 1, 0.143], [0, 0, 0, 1]]
117 ),
118 ),
119 "right_arm": OPWSolverCfg(
120 end_link_name="right_link6",
121 root_link_name="right_arm_base",
122 tcp=np.array(
123 [[-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 1, 0.143], [0, 0, 0, 1]]
124 ),
125 ),
126 },
127 "min_position_iters": 8,
128 "min_velocity_iters": 2,
129 "drive_pros": JointDrivePropertiesCfg(
130 stiffness={
131 "LEFT_JOINT[1-6]": 7e4,
132 "RIGHT_JOINT[1-6]": 7e4,
133 "LEFT_JOINT[7-8]": 3e2,
134 "RIGHT_JOINT[7-8]": 3e2,
135 },
136 damping={
137 "LEFT_JOINT[1-6]": 1e3,
138 "RIGHT_JOINT[1-6]": 1e3,
139 "LEFT_JOINT[7-8]": 3e1,
140 "RIGHT_JOINT[7-8]": 3e1,
141 },
142 max_effort={
143 "LEFT_JOINT[1-6]": 3e6,
144 "RIGHT_JOINT[1-6]": 3e6,
145 "LEFT_JOINT[7-8]": 3e3,
146 "RIGHT_JOINT[7-8]": 3e3,
147 },
148 ),
149 "attrs": RigidBodyAttributesCfg(
150 mass=0.1,
151 static_friction=0.95,
152 dynamic_friction=0.9,
153 linear_damping=0.7,
154 angular_damping=0.7,
155 contact_offset=0.001,
156 rest_offset=0.001,
157 restitution=0.01,
158 max_depenetration_velocity=1e1,
159 ),
160 }
161
162 def build_pk_serial_chain(
163 self, device: torch.device = torch.device("cpu"), **kwargs
164 ) -> Dict[str, "pk.SerialChain"]:
165 from embodichain.lab.sim.utility.solver_utils import (
166 create_pk_chain,
167 create_pk_serial_chain,
168 )
169
170 urdf_path = get_data_path("CobotMagicArm/CobotMagicNoGripper.urdf")
171 chain = create_pk_chain(urdf_path, device)
172
173 left_arm_chain = create_pk_serial_chain(
174 chain=chain, end_link_name="link6", root_link_name="base_link"
175 ).to(device=device)
176 right_arm_chain = create_pk_serial_chain(
177 chain=chain, end_link_name="link6", root_link_name="base_link"
178 ).to(device=device)
179 return {"left_arm": left_arm_chain, "right_arm": right_arm_chain}
180
181
182if __name__ == "__main__":
183 from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
184 from embodichain.lab.sim.robots import CobotMagicCfg
185
186 torch.set_printoptions(precision=5, sci_mode=False)
187
188 config = SimulationManagerCfg(headless=False, sim_device="cuda", num_envs=2)
189 sim = SimulationManager(config)
190
191 config = {
192 "init_pos": [0.0, 0.0, 1.0],
193 }
194
195 cfg = CobotMagicCfg.from_dict(config)
196 robot = sim.add_robot(cfg=cfg)
197
198 sim.init_gpu_physics()
199 print("CobotMagic added to the simulation.")
200
201 from IPython import embed
202
203 embed()
Step-by-Step Guide#
Create the configuration class inheriting from
RobotCfg:from __future__ import annotations from typing import Dict, List, Any import numpy as np from embodichain.lab.sim.cfg import ( RobotCfg, URDFCfg, JointDrivePropertiesCfg, RigidBodyAttributesCfg, ) from embodichain.lab.sim.solvers import SolverCfg, OPWSolverCfg from embodichain.lab.sim.utility.cfg_utils import merge_robot_cfg from embodichain.data import get_data_path from embodichain.utils import configclass @configclass class MyRobotCfg(RobotCfg): urdf_cfg: URDFCfg = None control_parts: Dict[str, List[str]] | None = None solver_cfg: Dict[str, "SolverCfg"] | None = None
Implement the ``from_dict`` class method for flexible initialization:
@classmethod def from_dict(cls, init_dict: Dict[str, Any]) -> "MyRobotCfg": cfg = cls() default_cfgs = cls()._build_default_cfgs() for key, value in default_cfgs.items(): setattr(cfg, key, value) cfg = merge_robot_cfg(cfg, init_dict) return cfg
Define ``_build_default_cfgs`` with your robot’s defaults:
@staticmethod def _build_default_cfgs() -> Dict[str, Any]: # URDF path urdf_path = get_data_path("MyRobot/my_robot.urdf") # URDF configuration (for multi-component robots) urdf_cfg = URDFCfg( components=[ { "component_type": "arm", "urdf_path": urdf_path, "transform": np.eye(4), # 4x4 transform matrix }, ] ) # Control parts - group joints for control control_parts = { "arm": [ "JOINT1", "JOINT2", "JOINT3", "JOINT4", "JOINT5", "JOINT6", ], "gripper": ["JOINT7", "JOINT8"], } # Solver configuration for IK solver_cfg = { "arm": OPWSolverCfg( end_link_name="link6", root_link_name="base_link", tcp=np.array([...]), # Tool center point transform ), } # Drive properties - joint physics parameters drive_pros = JointDrivePropertiesCfg( stiffness={ "JOINT[1-6]": 7e4, # Regex pattern for joints 1-6 "JOINT[7-8]": 3e2, }, damping={ "JOINT[1-6]": 1e3, "JOINT[7-8]": 3e1, }, max_effort={ "JOINT[1-6]": 3e6, "JOINT[7-8]": 3e3, }, ) return { "uid": "MyRobot", "urdf_cfg": urdf_cfg, "control_parts": control_parts, "solver_cfg": solver_cfg, "drive_pros": drive_pros, "attrs": RigidBodyAttributesCfg( mass=0.1, static_friction=0.95, dynamic_friction=0.9, linear_damping=0.7, angular_damping=0.7, ), }
Implement ``build_pk_serial_chain`` for PyTorch-Kinematics:
def build_pk_serial_chain( self, device: torch.device = torch.device("cpu"), **kwargs ) -> Dict[str, "pk.SerialChain"]: from embodichain.lab.sim.utility.solver_utils import ( create_pk_chain, create_pk_serial_chain, ) urdf_path = get_data_path("MyRobot/my_robot.urdf") chain = create_pk_chain(urdf_path, device) arm_chain = create_pk_serial_chain( chain=chain, end_link_name="link6", root_link_name="base_link" ).to(device=device) return {"arm": arm_chain}
Register in
embodichain/lab/sim/robots/__init__.py:from .my_robot import MyRobotCfg
—
Approach 2: Package-Based Robot (Complex Robots)#
Use this approach for robots with multiple variants (e.g., different arm types, versions, or configurations).
File Structure#
For complex robots, create a package directory:
robots/
└── my_robot/
├── __init__.py # Exports the main config class
├── types.py # Enums for robot variants
├── params.py # Kinematics parameters
├── utils.py # Manager classes and builders
└── cfg.py # Main configuration class
Step-by-Step Guide#
types.py - Define enums for robot variants:
from enum import Enum class MyRobotVersion(Enum): V010 = "v010" V020 = "v020" class MyRobotArmKind(Enum): STANDARD = "standard" EXTENDED = "extended" class MyRobotSide(Enum): LEFT = "left" RIGHT = "right"
params.py - Define kinematics parameters:
from dataclasses import dataclass import numpy as np from typing import Optional @dataclass class MyRobotArmKineParams: arm_side: MyRobotSide arm_kind: MyRobotArmKind version: MyRobotVersion dh_params: np.ndarray = None # DH parameters (N x 4) qpos_limits: np.ndarray = None # Joint limits (N x 2) link_lengths: np.ndarray = None # Link lengths T_b_ob: np.ndarray = None # Base to origin transform T_e_oe: np.ndarray = None # End-effector transform
utils.py - Manager classes and builder functions:
class ArmManager: """Manages arm URDF and configuration.""" pass def build_my_robot_assembly_urdf_cfg(...): """Build URDF assembly from components.""" pass def build_my_robot_cfg(...): """Build complete robot configuration.""" pass
cfg.py - Main configuration class:
@configclass class MyRobotCfg(RobotCfg): version: MyRobotVersion = MyRobotVersion.V010 arm_kind: MyRobotArmKind = MyRobotArmKind.STANDARD @classmethod def from_dict(cls, init_dict: Dict) -> "MyRobotCfg": # Implementation similar to single-file approach pass
__init__.py - Export the config:
from .cfg import MyRobotCfg
Register in
robots/__init__.py:from .my_robot import *
—
Key Configuration Parameters#
Regardless of the approach, your robot config needs these core parameters:
URDF Configuration#
The URDFCfg allows composing robots from multiple URDF files:
urdf_cfg = URDFCfg(
components=[
{
"component_type": "arm",
"urdf_path": arm_urdf,
"transform": np.eye(4),
},
{
"component_type": "gripper",
"urdf_path": gripper_urdf,
"transform": gripper_transform,
},
]
)
Control Parts#
Group joints logically for different control modes:
control_parts = {
"arm": ["JOINT1", "JOINT2", "JOINT3", "JOINT4", "JOINT5", "JOINT6"],
"gripper": ["JOINT7", "JOINT8"],
}
Use regex patterns for flexible matching:
- "JOINT[1-6]" matches JOINT1 through JOINT6
- "(LEFT|RIGHT)_ARM.*" matches all arm joints
Drive Properties#
Configure joint physics behavior:
drive_pros = JointDrivePropertiesCfg(
stiffness={
"ARM_JOINTS": 1e4, # High stiffness for arm joints
"GRIPPER_JOINTS": 3e2, # Lower stiffness for gripper
},
damping={
"ARM_JOINTS": 1e3,
"GRIPPER_JOINTS": 3e1,
},
max_effort={
"ARM_JOINTS": 1e5,
"GRIPPER_JOINTS": 1e3,
},
)
IK Solver Configuration#
Choose the appropriate solver for your robot:
OPWSolverCfg: For 6-axis industrial arms (like CobotMagic)
SRSSolverCfg: For robots with specific kinematics (like DexforceW1)
SolverCfg: Generic solver configuration
solver_cfg = {
"arm": OPWSolverCfg(
end_link_name="link6",
root_link_name="base_link",
tcp=np.array([...]), # Tool center point
),
}
—
Using Your Robot#
After adding the robot, use it in your code:
from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
from embodichain.lab.sim.robots import MyRobotCfg
# Create simulation
sim_cfg = SimulationManagerCfg(headless=False, num_envs=2)
sim = SimulationManager(sim_cfg)
# Create robot config
robot_cfg = MyRobotCfg.from_dict({
"uid": "my_robot",
})
# Add robot to simulation
robot = sim.add_robot(cfg=robot_cfg)
—
Testing Your Robot#
Add a test block at the bottom of your robot config file:
if __name__ == "__main__":
from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
sim_cfg = SimulationManagerCfg(headless=True, num_envs=2)
sim = SimulationManager(sim_cfg)
robot_cfg = MyRobotCfg.from_dict({"uid": "my_robot"})
robot = sim.add_robot(cfg=robot_cfg)
print("Robot added successfully!")
—
Best Practices#
Use the
@configclassdecorator for all config classesProvide
from_dictmethod for flexible initializationUse regex patterns for joint names in drive properties
Keep kinematics parameters separate in
params.pyfor complex robotsInclude
build_pk_serial_chainmethod for IK supportAdd
to_dictandsave_to_filemethods for serializationTest with
__main__block before integratingAdd robot documentation in
docs/source/resources/robot/for user reference
—
Adding Robot Documentation#
When adding a new robot, create documentation in docs/source/resources/robot/ to help users understand and use your robot.
File Location#
Create a markdown file: docs/source/resources/robot/my_robot.md
Recommended Structure#
# MyRobot
Brief description of the robot and its manufacturer.
<div style="text-align: center;">
<img src="../../_static/robots/my_robot.jpg" alt="MyRobot" style="height: 400px; width: auto;"/>
<p><b>MyRobot</b></p>
</div>
## Key Features
- Feature 1
- Feature 2
- Feature 3
---
## Robot Parameters
| Parameter | Description |
|-----------|-------------|
| Joints | Number of joints |
| DOF | Degrees of freedom |
| ... | ... |
---
## Quick Initialization Example
```python
from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
from embodichain.lab.sim.robots import MyRobotCfg
config = SimulationManagerCfg(headless=False, sim_device="cpu", num_envs=2)
sim = SimulationManager(config)
robot = sim.add_robot(cfg=MyRobotCfg.from_dict({}))
```
---
## Configuration Parameters
### Main Configuration Items
- **uid**: Unique identifier
- **urdf_cfg**: URDF configuration
- **control_parts**: Control groups
- **solver_cfg**: IK solver configuration
- **drive_pros**: Joint drive properties
- **attrs**: Physical attributes
### Custom Usage Example
```python
custom_cfg = {
"uid": "my_robot",
# Add parameters
}
cfg = MyRobotCfg.from_dict(custom_cfg)
robot = sim.add_robot(cfg=cfg)
```
---
## References
- Manufacturer product page
- URDF file paths
- Related documentation
Register the Robot in Index#
After creating the robot documentation, add it to the index file at docs/source/resources/robot/index.rst:
.. toctree::
:maxdepth: 1
Dexforce W1 <dexforce_w1.md>
CobotMagic <cobotmagic.md>
MyRobot <my_robot.md> # Add your robot here
—
Next Steps#
After adding your robot:
Add robot documentation in
docs/source/resources/robot/Update
docs/source/resources/robot/index.rstto include the new robotAdd task environments that use your robot
Configure sensors (cameras, force sensors)
Implement custom IK solvers if needed
Add motion planning support