SRDF extends URDF with semantic information for planning, collision handling, and operation.
The Semantic Robot Description Format (SRDF) is a companion to the URDF that adds semantic meaning to your robot:
- Planning groups – Define manipulator arms, mobile bases, and other functional units
- Collision rules – Specify which link pairs are always allowed to collide (self-contact, adjacent joints)
- Default poses – Store named configurations like "home", "stowed", or "ready"
- Tool definitions – Define and store tool center points (TCPs) for end-effectors
- Plugins – Configure kinematics solvers, collision checkers, and other algorithms
While your URDF describes what the robot is, your SRDF describes how to use it for planning and control.
Getting Started? See Tesseract SRDF Parsing Example for a complete walkthrough of loading and using SRDF files in code.
Key Concepts
Why SRDF Matters**
Consider a 7-DOF manipulator with a gripper. Your URDF defines every link, joint, mass, and geometry. But planners also need to know:
- Which joints move together as a planning group (the arm, not the gripper in isolation)
- That the gripper fingers can collide with each other (allowed, not an error)
- That adjacent joints in the arm occasionally touch (self-contact, expected)
- Where the tool sits relative to the wrist flange (TCP offset)
Without this semantic information, collision checkers flag false positives, and planners can be overconstrained. SRDF makes this knowledge explicit and reusable.
URDF vs SRDF**
| Aspect | URDF | SRDF |
| Purpose | Kinematic and dynamic structure | Semantic meaning for planning |
| Content | Links, joints, masses, geometry, frames | Groups, collision rules, poses, TCPs |
| Use Case | Load robot structure into tools | Configure planners and collision handlers |
| Required | Yes, always | Often yes (strongly recommended) |
Standard SRDF Features
Tesseract fully supports these core SRDF elements:
Planning Groups
Pinpoint which joints and links move together as a functional unit. This is essential for planning—you plan the arm without the gripper, the gripper without the arm, or both together depending on your task.
Groups can be defined in two ways:
By Joint List**
Example SRDF groups definition:
<group name="manipulator">
<chain base_link="base_link" tip_link="tool0" />
</group>
<group name="manipulator_joint_group">
<joint name="joint_a1"/>
<joint name="joint_a2"/>
<joint name="joint_a3"/>
<joint name="joint_a4"/>
<joint name="joint_a5"/>
<joint name="joint_a6"/>
<joint name="joint_a7"/>
</group>
Once defined, you reference groups by name in planning, collision, and kinematics configuration.
Named Configurations (Group States)
Define and store named robot configurations (joint position sets) in your SRDF. These are typically used for operational poses like:
- "home" – default ready position
- "stowed" – safe transport or storage position
- "ready" – prepared for work
- "reset" – known good state for initialization
Once defined, planners can query configurations by name and use them as goal states or initialization points. This avoids hard-coding joint angles throughout your application code.
Tool Center Points (TCPs)
Define the pose of your tool (end-effector) relative to the robot's wrist flange. Stored by name, TCPs are retrieved during planning and execution to compute tool positions and orientations in the world frame.
Common use cases:
- Welding torch tip offset from mounting bracket
- Gripper finger center for grasping
- Spray nozzle position for painting or coating
- Camera optical center for inspection tasks
Allowed Collision Matrix (ACM)
Specify which link pairs are allowed to be in collision. This is critical for realistic collision checking:
- Self-contact – Adjacent links in a serial chain often come into contact (expected, not an error)
- Gripper fingers – Gripper fingers must collide with each other to grasp
- Mounted devices – Sensors, cables, or mounting brackets that always touch their base
- Tool and work – Your tool intentionally contacts the workpiece
Without an ACM, collision checkers report self-contact as failures, blocking valid plans. The ACM tells planners: "This collision is expected and allowed; don't treat it as a constraint violation."
Example: A 7-DOF arm with a parallel gripper needs to allow:
- Link 5 ↔ Link 6 (adjacent joint, expected contact)
- Finger A ↔ Finger B (gripper mechanism)
- Gripper body ↔ grasped object (intentional contact during work)
Tesseract-Specific Extensions
Beyond standard SRDF, Tesseract adds configuration files for kinematics solvers and collision management.
Collision Management Configuration
Tesseract uses a YAML configuration file to define which collision checking algorithm(s) to use and which plugins provide those implementations.
You can run multiple collision algorithms simultaneously and configure them with different parameters (e.g., discrete collision for planning, continuous collision for trajectory validation). The configuration specifies which plugin to use as the default and where to search for plugin libraries.
Configuration Structure**
contact_manager_plugins:
search_paths: [<directories to search for plugins>]
search_libraries: [<optional libraries to search>]
discrete_plugins:
default: <default discrete collision checker name>
plugins:
<collision checker name>:
class: <C++ class implementing the checker>
continuous_plugins:
default: <default continuous collision checker name>
plugins:
<collision checker name>:
class: <C++ class implementing the checker>
Example Configuration**
contact_manager_plugins:
search_paths:
- /usr/local/lib
search_libraries:
- tesseract_collision_bullet_factories
- tesseract_collision_fcl_factories
discrete_plugins:
default: BulletDiscreteBVHManager
plugins:
BulletDiscreteBVHManager:
class: BulletDiscreteBVHManagerFactory
BulletDiscreteSimpleManager:
class: BulletDiscreteSimpleManagerFactory
FCLDiscreteBVHManager:
class: FCLDiscreteBVHManagerFactory
continuous_plugins:
default: BulletCastBVHManager
plugins:
BulletCastBVHManager:
class: BulletCastBVHManagerFactory
BulletCastSimpleManager:
class: BulletCastSimpleManagerFactory
Kinematics Solver Configuration (Optional)
Define which forward kinematics (FK) and inverse kinematics (IK) solvers to use for each planning group. Tesseract supports multiple solvers and lets you combine them when appropriate (e.g., an analytical solver for speed, plus a numerical solver for redundancy resolution).
You specify solvers per planning group so different arms, positioners, or mobile bases can use different algorithms.
Configuration Structure**
kinematics_plugins:
search_paths: [<directories to search for plugins>]
search_libraries: [<optional libraries>]
forward_kinematics:
<group name>:
default: <solver to use by default>
plugins:
<solver name>:
class: <C++ class name>
config: {<solver-specific parameters>}
inverse_kinematics:
<group name>:
default: <solver to use by default>
plugins:
<solver name>:
class: <C++ class name>
config: {<solver-specific parameters>}
Example Configuration**
kinematic_plugins:
search_libraries:
- tesseract_kinematics_kdl_factories
inv_kin_plugins:
manipulator:
default: KDLInvKinChainLMA
plugins:
KDLInvKinChainLMA:
class: KDLInvKinChainLMAFactory
config:
base_link: base_link
tip_link: iiwa_tool0
KDLInvKinChainNR:
class: KDLInvKinChainNRFactory
config:
base_link: base_link
tip_link: iiwa_tool0
Available Forward Kinematics Solvers
KDL (Kinematics Dynamics Library)**
A robust, general-purpose numerical FK solver that works with any kinematic structure. No configuration needed for basic use.
KDLFwdKinChain:
class: KDLFwdKinChainFactory
config:
base_link: base_link
tip_link: tool0
See kdl_fk for detailed documentation.
Available Inverse Kinematics Solvers
Tesseract provides multiple IK solvers optimized for different robot structures and use cases. You can configure one solver as default and provide fallback solvers for redundancy or robustness.
OPW (Open-Loop Payload Workspace)
An analytical IK solver optimized for 6-DOF industrial robots (ABB, KUKA, Fanuc, etc.) with the geometry pattern: revolute-revolute-revolute-revolute-revolute-revolute.
Advantages:**
- Extremely fast (milliseconds to compute all solutions)
- Closed-form solution (no iterative convergence required)
- Multiple solutions automatically (arm above/below configurations)
Numerically stable
Requirements:**
- Robot must match the Pieper arm geometry
- Configuration parameters needed (arm dimensions, axis offsets)
OPWInvKin:
class: OPWInvKinFactory
config:
base_link: base_link
tip_link: tool0
params:
a1: 0.100
a2: -0.135
b: 0.00
c1: 0.615
c2: 0.705
c3: 0.755
c4: 0.085
offsets: [0, 0, -1.57079632679, 0, 0, 0]
sign_corrections: [1, 1, 1, 1, 1, 1]
See OPW (Open-Loop Payload Workspace) for detailed geometry requirements and configuration.
KDL Levenberg-Marquardt (LMA)
A numerical IK solver using the Levenberg-Marquardt optimization algorithm.
Use when:**
- Your robot doesn't match the OPW geometry (non-standard D-H parameters)
- You need IK for robots with non-6-DOF structure
Analytical solvers don't exist for your robot type
Trade-off:** Slower than analytical solvers, but more general.
KDLInvKinChainLMA:
class: KDLInvKinChainLMAFactory
config:
base_link: base_link
tip_link: tool0
See KDL Levenberg-Marquardt (LMA) for additional configuration options.
KDL Newton-Raphson (NR)
Another numerical IK solver using the Newton-Raphson iterative method.
Similar to KDL-LMA but:**
- Often converges faster (fewer iterations)
- May be less stable for far-from-solution starting points
- Good choice for real-time execution where speed matters
KDLInvKinChainNR:
class: KDLInvKinChainNRFactory
config:
base_link: base_link
tip_link: tool0
See KDL Newton-Raphson (NR) for detailed configuration.
Robot on Positioner (ROP)
Combine a custom robot IK solver with a sampled external axis (positioner, track, turntable) to find a larger solution space.
Example:** A 6-DOF arm mounted on a linear track. Your arm has IK, but the track position adds a 7th DOF. ROP samples the track at discrete intervals and solves arm IK at each track position.
Requirements:**
- A custom IK solver must already exist for the robot
- Positioner axis is sampled at specified resolution
ROPInvKin:
class: ROPInvKinFactory
config:
manipulator_reach: 2.0
positioner_sample_resolution:
- name: gantry_axis_1
value: 0.1
- name: gantry_axis_2
value: 0.1
positioner:
class: KDLFwdKinChainFactory
config:
base_link: world
tip_link: base_link
manipulator:
class: OPWInvKinFactory
config:
base_link: base_link
tip_link: tool0
params:
a1: 0.100
a2: -0.135
b: 0.00
c1: 0.615
c2: 0.705
c3: 0.755
c4: 0.086
offsets: [0, 0, -1.57079632679, 0, 0, 0]
sign_corrections: [1, 1, 1, 1, 1, 1]
See Robot on Positioner (ROP) for additional details.
Robot with External Positioner (REP)
Similar to ROP, but for an external positioner that can be reoriented independently (e.g., a rotary table holding the workpiece).
Example:** A 6-DOF welding robot with a workpiece on a turntable. The turntable orientation is a 7th DOF. REP samples turntable angles and solves robot IK for each orientation.
See Robot with External Positioner (REP) for configuration and use cases.