Configure Complex Kinematic Chains
Many components have complex kinematic chains and require an additional set of intermediate reference frames to use Viam’s Motion service.
- For example, an arm has a reference frame originating where the arm is attached to a surface, but it also has links and joints whose frames of reference matter when attempting to move the arm to a pose with
MoveToPosition()
.
If you want to implement a component with a complex kinematic chain that is not already built into the RDK, you need to add a file to your driver that details the attachment of the intermediate reference frames on the component.
This file can be a
Kinematic parameters
Viam supports two formats for supplying kinematic parameters to configure intermediate reference frames for a kinematic chain, defined as "kinematic_param_type"
:
- Spatial Vector Algebra (SVA): supplying reference frame information for each
link
and eachjoint
. - Denavit-Hartenberg (DH) parameters.
Info
Of the two methods, we prefer Spatial Vector Algebra over Denavit-Hartenberg because it allows you to specify link frames arbitrarily, which DH parameters are unable to guarantee. Additionally, if you are making your own robot and defining new drivers, incorrect SVA parameters are easier to troubleshoot than incorrect DH parameters.
This is an example
{
"name": "UR5e",
"kinematic_param_type": "SVA",
"links": [
{
"id": "base_link",
"parent": "world",
"translation": {
"x": 0,
"y": 0,
"z": 162.5
},
"geometry": {
"x": 120,
"y": 120,
"z": 260,
"translation": {
"x": 0,
"y": 0,
"z": 130
}
}
},
{
"id": "shoulder_link",
"parent": "shoulder_pan_joint",
"translation": {
"x": 0,
"y": 0,
"z": 0
}
},
{
"id": "upper_arm_link",
"parent": "shoulder_lift_joint",
"translation": {
"x": -425,
"y": 0,
"z": 0
},
"geometry": {
"x": 550,
"y": 150,
"z": 120,
"translation": {
"x": -215,
"y": -130,
"z": 0
}
}
},
{
"id": "forearm_link",
"parent": "elbow_joint",
"translation": {
"x": -392.2,
"y": 0,
"z": 0
},
"geometry": {
"x": 480,
"y": 120,
"z": 100,
"translation": {
"x": -190,
"y": 0,
"z": 0
}
}
},
{
"id": "wrist_1_link",
"parent": "wrist_1_joint",
"translation": {
"x": 0,
"y": -133.3,
"z": 0
},
"geometry": {
"x": 90,
"y": 130,
"z": 130,
"translation": {
"x": 0,
"y": -110,
"z": 0
}
}
},
{
"id": "wrist_2_link",
"parent": "wrist_2_joint",
"translation": {
"x": 0,
"y": 0,
"z": -99.7
},
"geometry": {
"x": 80,
"y": 150,
"z": 100,
"translation": {
"x": 0,
"y": 0,
"z": -100
}
}
},
{
"id": "ee_link",
"parent": "wrist_3_joint",
"translation": {
"x": 0,
"y": -99.6,
"z": 0
},
"orientation": {
"type": "ov_degrees",
"value": {
"x": 0,
"y": -1,
"z": 0,
"th": 90
}
}
}
],
"joints": [
{
"id": "shoulder_pan_joint",
"type": "revolute",
"parent": "base_link",
"axis": {
"x": 0,
"y": 0,
"z": 1
},
"max": 360,
"min": -360
},
{
"id": "shoulder_lift_joint",
"type": "revolute",
"parent": "shoulder_link",
"axis": {
"x": 0,
"y": -1,
"z": 0
},
"max": 360,
"min": -360
},
{
"id": "elbow_joint",
"type": "revolute",
"parent": "upper_arm_link",
"axis": {
"x": 0,
"y": -1,
"z": 0
},
"max": 180,
"min": -180
},
{
"id": "wrist_1_joint",
"type": "revolute",
"parent": "forearm_link",
"axis": {
"x": 0,
"y": -1,
"z": 0
},
"max": 360,
"min": -360
},
{
"id": "wrist_2_joint",
"type": "revolute",
"parent": "wrist_1_link",
"axis": {
"x": 0,
"y": 0,
"z": -1
},
"max": 360,
"min": -360
},
{
"id": "wrist_3_joint",
"type": "revolute",
"parent": "wrist_2_link",
"axis": {
"x": 0,
"y": -1,
"z": 0
},
"max": 360,
"min": -360
}
]
}
{
"name": "UR5e",
"kinematic_param_type": "DH",
"dhParams": [
{
"id": "base",
"parent": "world",
"a": 0,
"d": 162.5,
"alpha": 1.57079632679,
"max": 360,
"min": -360
},
{
"id": "shoulder",
"parent": "base",
"a": -425,
"d": 0,
"alpha": 0,
"max": 360,
"min": -360
},
{
"id": "elbow",
"parent": "shoulder",
"a": -392.2,
"d": 0,
"alpha": 0,
"max": 180,
"min": -180
},
{
"id": "wrist_1",
"parent": "elbow",
"a": 0,
"d": 133.3,
"alpha": 1.57079632679,
"max": 360,
"min": -360
},
{
"id": "wrist_2",
"parent": "wrist_1",
"a": 0,
"d": 99.7,
"alpha": -1.57079632679,
"max": 360,
"min": -360
},
{
"id": "wrist_3",
"parent": "wrist_2",
"a": 0,
"d": 99.6,
"alpha": 0,
"max": 360,
"min": -360
}
]
}
Info
These reference frames are ingested by the frame system.
They are not exposed in the client SDKs, with one exception.
If your resource is an arm component, you can use the GetKinematics()
method to access its kinematics information.
Have questions, or want to meet other people working on robots? Join our Community Discord.
If you notice any issues with the documentation, feel free to file an issue or edit this file.
Was this page helpful?
Glad to hear it! If you have any other feedback please let us know:
We're sorry about that. To help us improve, please tell us what we can do better:
Thank you!