Skip to content

tesseract_robotics.tesseract_scene_graph

Scene graph elements: links, joints, and kinematic tree.

SceneGraph

The kinematic tree structure.

Python
from tesseract_robotics.tesseract_scene_graph import SceneGraph

graph = SceneGraph()
graph.setName("my_robot")

# Add elements
graph.addLink(link)
graph.addJoint(joint)

# Query structure
links = graph.getLinks()
joints = graph.getJoints()
root = graph.getRoot()

# Find elements
link = graph.getLink("base_link")
joint = graph.getJoint("joint_1")

# Kinematic queries
children = graph.getChildren("base_link")
parent = graph.getParent("tool0")
path = graph.getShortestPath("base_link", "tool0")

A rigid body in the kinematic tree.

Python
from tesseract_robotics.tesseract_scene_graph import Link, Visual, Collision
from tesseract_robotics.tesseract_geometry import Box
from tesseract_robotics.tesseract_common import Isometry3d

# Create link
link = Link("my_link")

# Add visual geometry
visual = Visual()
visual.geometry = Box(0.1, 0.1, 0.1)
visual.origin = Isometry3d.Identity()
link.addVisual(visual)  # Note: use addVisual(), not visual.append()

# Add collision geometry
collision = Collision()
collision.geometry = Box(0.1, 0.1, 0.1)
collision.origin = Isometry3d.Identity()
link.addCollision(collision)

# Access geometries
visuals = link.visual       # list[Visual]
collisions = link.collision # list[Collision]

# Clear geometries
link.clearVisual()
link.clearCollision()

Visual

Visual representation of a link.

Python
from tesseract_robotics.tesseract_scene_graph import Visual, Material

visual = Visual()
visual.name = "visual_0"
visual.geometry = geometry
visual.origin = transform

# Material (optional)
material = Material()
material.name = "red"
material.color = np.array([1.0, 0.0, 0.0, 1.0])  # RGBA
visual.material = material

Collision

Collision geometry of a link.

Python
from tesseract_robotics.tesseract_scene_graph import Collision

collision = Collision()
collision.name = "collision_0"
collision.geometry = geometry
collision.origin = transform

Joint

Connection between two links.

Python
from tesseract_robotics.tesseract_scene_graph import Joint, JointType

joint = Joint("joint_1")
joint.type = JointType.REVOLUTE
joint.parent_link_name = "link_0"
joint.child_link_name = "link_1"
joint.parent_to_joint_origin_transform = Isometry3d.Identity()
joint.axis = np.array([0, 0, 1])  # rotation axis

JointType

Type Description
REVOLUTE Rotational with limits
CONTINUOUS Rotational, no limits
PRISMATIC Linear sliding
FIXED No motion
FLOATING 6-DOF free motion
PLANAR 2D motion in a plane

JointLimits

Python
from tesseract_robotics.tesseract_scene_graph import JointLimits

limits = JointLimits()
limits.lower = -3.14
limits.upper = 3.14
limits.velocity = 2.0
limits.acceleration = 5.0
limits.effort = 100.0

joint.limits = limits

JointDynamics

Python
from tesseract_robotics.tesseract_scene_graph import JointDynamics

dynamics = JointDynamics()
dynamics.damping = 0.1
dynamics.friction = 0.05

joint.dynamics = dynamics

JointMimic

Python
from tesseract_robotics.tesseract_scene_graph import JointMimic

mimic = JointMimic()
mimic.joint_name = "joint_1"  # joint to mimic
mimic.multiplier = 1.0
mimic.offset = 0.0

joint.mimic = mimic

Inertial

Mass and inertia properties.

Python
from tesseract_robotics.tesseract_scene_graph import Inertial

inertial = Inertial()
inertial.origin = Isometry3d.Identity()
inertial.mass = 1.0
inertial.ixx = 0.01
inertial.iyy = 0.01
inertial.izz = 0.01
inertial.ixy = 0.0
inertial.ixz = 0.0
inertial.iyz = 0.0

link.inertial = inertial

SceneState

Current state of the scene graph.

Python
from tesseract_robotics.tesseract_scene_graph import SceneState

state = env.getState()

# Joint positions
positions = state.joints  # dict[str, float]

# Link transforms
transforms = state.link_transforms  # dict[str, Isometry3d]
tcp_pose = transforms["tool0"]

Auto-generated API Reference

JointType_UNKNOWN module-attribute

Python
JointType_UNKNOWN: JointType = UNKNOWN

JointType_REVOLUTE module-attribute

Python
JointType_REVOLUTE: JointType = REVOLUTE

JointType_CONTINUOUS module-attribute

Python
JointType_CONTINUOUS: JointType = CONTINUOUS

JointType_PRISMATIC module-attribute

Python
JointType_PRISMATIC: JointType = PRISMATIC

JointType_FLOATING module-attribute

Python
JointType_FLOATING: JointType = FLOATING

JointType_PLANAR module-attribute

Python
JointType_PLANAR: JointType = PLANAR

JointType_FIXED module-attribute

Python
JointType_FIXED: JointType = FIXED

JointType

Bases: Enum

UNKNOWN class-attribute instance-attribute

Python
UNKNOWN = 0

REVOLUTE class-attribute instance-attribute

Python
REVOLUTE = 1

CONTINUOUS class-attribute instance-attribute

Python
CONTINUOUS = 2

PRISMATIC class-attribute instance-attribute

Python
PRISMATIC = 3

FLOATING class-attribute instance-attribute

Python
FLOATING = 4

PLANAR class-attribute instance-attribute

Python
PLANAR = 5

FIXED class-attribute instance-attribute

Python
FIXED = 6

JointDynamics

damping property writable

Python
damping: float

friction property writable

Python
friction: float

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: JointDynamics) -> bool

__ne__

Python
__ne__(arg: JointDynamics) -> bool

__repr__

Python
__repr__() -> str

JointLimits

lower property writable

Python
lower: float

upper property writable

Python
upper: float

effort property writable

Python
effort: float

velocity property writable

Python
velocity: float

acceleration property writable

Python
acceleration: float

jerk property writable

Python
jerk: float

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: JointLimits) -> bool

__ne__

Python
__ne__(arg: JointLimits) -> bool

__repr__

Python
__repr__() -> str

JointSafety

soft_upper_limit property writable

Python
soft_upper_limit: float

soft_lower_limit property writable

Python
soft_lower_limit: float

k_position property writable

Python
k_position: float

k_velocity property writable

Python
k_velocity: float

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: JointSafety) -> bool

__ne__

Python
__ne__(arg: JointSafety) -> bool

JointCalibration

reference_position property writable

Python
reference_position: float

rising property writable

Python
rising: float

falling property writable

Python
falling: float

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: JointCalibration) -> bool

__ne__

Python
__ne__(arg: JointCalibration) -> bool

JointMimic

offset property writable

Python
offset: float

multiplier property writable

Python
multiplier: float

joint_name property writable

Python
joint_name: str

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: JointMimic) -> bool

__ne__

Python
__ne__(arg: JointMimic) -> bool

Joint

type property writable

Python
type: JointType

axis property writable

Python
axis: Annotated[NDArray[float64], dict(shape=3, order=C)]
Python
child_link_name: str
Python
parent_link_name: str

parent_to_joint_origin_transform property writable

Python
parent_to_joint_origin_transform: 'Eigen::Transform<double, 3, 1, 0>'

dynamics property writable

Python
dynamics: JointDynamics

limits property writable

Python
limits: JointLimits

safety property writable

Python
safety: JointSafety

calibration property writable

Python
calibration: JointCalibration

mimic property writable

Python
mimic: JointMimic

getName

Python
getName() -> str

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: Joint) -> bool

__ne__

Python
__ne__(arg: Joint) -> bool

__repr__

Python
__repr__() -> str

Material

texture_filename property writable

Python
texture_filename: str

color property writable

Python
color: Annotated[NDArray[float64], dict(shape=4, order=C)]

getName

Python
getName() -> str

getDefaultMaterial staticmethod

Python
getDefaultMaterial() -> Material

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: Material) -> bool

__ne__

Python
__ne__(arg: Material) -> bool

Inertial

origin property writable

Python
origin: 'Eigen::Transform<double, 3, 1, 0>'

mass property writable

Python
mass: float

ixx property writable

Python
ixx: float

ixy property writable

Python
ixy: float

ixz property writable

Python
ixz: float

iyy property writable

Python
iyy: float

iyz property writable

Python
iyz: float

izz property writable

Python
izz: float

__init__

Python
__init__() -> None

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: Inertial) -> bool

__ne__

Python
__ne__(arg: Inertial) -> bool

Visual

origin property writable

Python
origin: 'Eigen::Transform<double, 3, 1, 0>'

geometry property writable

Python
geometry: Geometry

material property writable

Python
material: Material

name property writable

Python
name: str

__init__

Python
__init__() -> None

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: Visual) -> bool

__ne__

Python
__ne__(arg: Visual) -> bool

Collision

origin property writable

Python
origin: 'Eigen::Transform<double, 3, 1, 0>'

geometry property writable

Python
geometry: Geometry

name property writable

Python
name: str

__init__

Python
__init__() -> None

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: Collision) -> bool

__ne__

Python
__ne__(arg: Collision) -> bool

inertial property writable

Python
inertial: Inertial

visual property writable

Python
visual: list[Visual]

collision property writable

Python
collision: list[Collision]

getName

Python
getName() -> str

addVisual

Python
addVisual(visual: Visual) -> None

Add a Visual to this link

addCollision

Python
addCollision(collision: Collision) -> None

Add a Collision to this link

clearVisual

Python
clearVisual() -> None

Clear all Visual elements from this link

clearCollision

Python
clearCollision() -> None

Clear all Collision elements from this link

clear

Python
clear() -> None

__eq__

Python
__eq__(arg: Link) -> bool

__ne__

Python
__ne__(arg: Link) -> bool

__repr__

Python
__repr__() -> str

ShortestPath

Python
links: list[str]

joints property writable

Python
joints: list[str]

active_joints property writable

Python
active_joints: list[str]

__init__

Python
__init__() -> None

SceneGraph

__init__

Python
__init__(name: str = '') -> None

clone

Python
clone() -> SceneGraph

clear

Python
clear() -> None

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

setRoot

Python
setRoot(name: str) -> bool

getRoot

Python
getRoot() -> str
Python
getLink(name: str) -> Link
Python
getLinks() -> list[Link]
Python
getLeafLinks() -> list[Link]
Python
removeLink(name: str, recursive: bool = False) -> bool
Python
moveLink(joint: Joint) -> bool

setLinkVisibility

Python
setLinkVisibility(name: str, visibility: bool) -> None

getLinkVisibility

Python
getLinkVisibility(name: str) -> bool

setLinkCollisionEnabled

Python
setLinkCollisionEnabled(name: str, enabled: bool) -> None

getLinkCollisionEnabled

Python
getLinkCollisionEnabled(name: str) -> bool

addJoint

Python
addJoint(joint: Joint) -> bool

getJoint

Python
getJoint(name: str) -> Joint

removeJoint

Python
removeJoint(name: str, recursive: bool = False) -> bool

moveJoint

Python
moveJoint(name: str, parent_link: str) -> bool

getJoints

Python
getJoints() -> list[Joint]

getActiveJoints

Python
getActiveJoints() -> list[Joint]

changeJointOrigin

Python
changeJointOrigin(name: str, new_origin: 'Eigen::Transform<double, 3, 1, 0>') -> bool

changeJointLimits

Python
changeJointLimits(name: str, limits: JointLimits) -> bool

changeJointPositionLimits

Python
changeJointPositionLimits(name: str, lower: float, upper: float) -> bool

changeJointVelocityLimits

Python
changeJointVelocityLimits(name: str, limit: float) -> bool

changeJointAccelerationLimits

Python
changeJointAccelerationLimits(name: str, limit: float) -> bool

changeJointJerkLimits

Python
changeJointJerkLimits(name: str, limit: float) -> bool

getJointLimits

Python
getJointLimits(name: str) -> JointLimits

addAllowedCollision

Python
addAllowedCollision(link_name1: str, link_name2: str, reason: str) -> None

clearAllowedCollisions

Python
clearAllowedCollisions() -> None

isCollisionAllowed

Python
isCollisionAllowed(link_name1: str, link_name2: str) -> bool

getAllowedCollisionMatrix

Python
getAllowedCollisionMatrix() -> 'tesseract_common::AllowedCollisionMatrix'

Get the allowed collision matrix

Python
getSourceLink(joint_name: str) -> Link
Python
getTargetLink(joint_name: str) -> Link

getInboundJoints

Python
getInboundJoints(link_name: str) -> list[Joint]

getOutboundJoints

Python
getOutboundJoints(link_name: str) -> list[Joint]

isAcyclic

Python
isAcyclic() -> bool

isTree

Python
isTree() -> bool

isEmpty

Python
isEmpty() -> bool

getAdjacentLinkNames

Python
getAdjacentLinkNames(name: str) -> list[str]

getInvAdjacentLinkNames

Python
getInvAdjacentLinkNames(name: str) -> list[str]

getLinkChildrenNames

Python
getLinkChildrenNames(name: str) -> list[str]

getJointChildrenNames

Python
getJointChildrenNames(name: str) -> list[str]

getShortestPath

Python
getShortestPath(root: str, tip: str) -> ShortestPath

saveDOT

Python
saveDOT(path: str) -> None

__eq__

Python
__eq__(arg: SceneGraph) -> bool

__ne__

Python
__ne__(arg: SceneGraph) -> bool

__repr__

Python
__repr__() -> str