Skip to content

tesseract_robotics.tesseract_common

Common types, utilities, and resource handling.

Transforms

Isometry3d

Rigid body transformation (rotation + translation).

Python
from tesseract_robotics.tesseract_common import Isometry3d
import numpy as np

# Identity transform
pose = Isometry3d.Identity()

# From 4x4 matrix
mat = np.eye(4)
mat[:3, 3] = [0.5, 0.2, 0.3]
pose = Isometry3d(mat)

# Access components
position = pose.translation()  # np.array([x, y, z])
rotation = pose.rotation()     # 3x3 rotation matrix
matrix = pose.matrix()         # 4x4 homogeneous matrix

# Transform operations
pose.translate([0.1, 0, 0])    # translate in place
pose.rotate(rotation_matrix)   # rotate in place
combined = pose1 * pose2       # compose transforms

Quaterniond

Quaternion rotation (w, x, y, z).

Python
from tesseract_robotics.tesseract_common import Quaterniond

q = Quaterniond(w=1.0, x=0.0, y=0.0, z=0.0)  # identity
q = Quaterniond.Identity()

# Access
print(f"w={q.w()}, x={q.x()}, y={q.y()}, z={q.z()}")
rotation_matrix = q.toRotationMatrix()

AngleAxisd

Axis-angle rotation representation.

Python
from tesseract_robotics.tesseract_common import AngleAxisd
import numpy as np

# 90 degrees around Z axis
aa = AngleAxisd(np.pi/2, np.array([0, 0, 1]))
rotation_matrix = aa.toRotationMatrix()

Resource Locators

GeneralResourceLocator

Resolves package:// URLs to file paths.

Python
from tesseract_robotics.tesseract_common import GeneralResourceLocator

locator = GeneralResourceLocator()

# Resolve package URL
resource = locator.locateResource("package://tesseract_support/urdf/abb_irb2400.urdf")
path = resource.getFilePath()

BytesResource

In-memory resource from bytes.

Python
from tesseract_robotics.tesseract_common import BytesResource

data = b"<robot name='test'></robot>"
resource = BytesResource("robot.urdf", data)

Collision

AllowedCollisionMatrix

Defines which link pairs to skip during collision checking.

Python
from tesseract_robotics.tesseract_common import AllowedCollisionMatrix

acm = AllowedCollisionMatrix()

# Allow collision between links
acm.addAllowedCollision("link_1", "link_2", "Adjacent links")

# Check if allowed
is_allowed = acm.isCollisionAllowed("link_1", "link_2")

# Remove entry
acm.removeAllowedCollision("link_1", "link_2")

# Clear all
acm.clearAllowedCollisions()

CollisionMarginData

Configure collision margins per link pair.

Python
from tesseract_robotics.tesseract_common import CollisionMarginData

margins = CollisionMarginData()
margins.setDefaultCollisionMargin(0.025)
margins.setPairCollisionMargin("link_a", "link_b", 0.05)

default = margins.getDefaultCollisionMargin()
pair_margin = margins.getPairCollisionMargin("link_a", "link_b")

State

JointState

Joint positions and velocities.

Python
from tesseract_robotics.tesseract_common import JointState

state = JointState()
state.joint_names = ["j1", "j2", "j3"]
state.position = np.array([0.0, 0.5, -0.5])
state.velocity = np.array([0.0, 0.0, 0.0])

KinematicLimits

Joint position, velocity, acceleration limits.

Python
from tesseract_robotics.tesseract_common import KinematicLimits

limits = kin_group.getLimits()
print(f"Position min: {limits.joint_limits.col(0)}")
print(f"Position max: {limits.joint_limits.col(1)}")
print(f"Velocity: {limits.velocity_limits}")
print(f"Acceleration: {limits.acceleration_limits}")

Manipulator Info

ManipulatorInfo

Describes a kinematic group configuration.

Python
from tesseract_robotics.tesseract_common import ManipulatorInfo

info = ManipulatorInfo()
info.manipulator = "manipulator"        # group name
info.working_frame = "base_link"        # reference frame
info.tcp_frame = "tool0"                # tool center point
info.tcp_offset = Isometry3d.Identity() # optional TCP offset

Logging

Control console_bridge logging level.

Python
from tesseract_robotics.tesseract_common import (
    getLogLevel, setLogLevel,
    CONSOLE_BRIDGE_LOG_NONE,
    CONSOLE_BRIDGE_LOG_ERROR,
    CONSOLE_BRIDGE_LOG_WARN,
    CONSOLE_BRIDGE_LOG_INFO,
    CONSOLE_BRIDGE_LOG_DEBUG,
)

# Suppress warnings
setLogLevel(CONSOLE_BRIDGE_LOG_ERROR)

# Enable debug output
setLogLevel(CONSOLE_BRIDGE_LOG_DEBUG)

Container Types

Type Description
TransformMap dict[str, Isometry3d] - link name to transform
VectorIsometry3d list[Isometry3d]
VectorVector3d list[np.ndarray] - list of 3D points

Auto-generated API Reference

CollisionMarginOverrideType module-attribute

Python
CollisionMarginOverrideType: TypeAlias = CollisionMarginPairOverrideType

CONSOLE_BRIDGE_LOG_DEBUG module-attribute

Python
CONSOLE_BRIDGE_LOG_DEBUG: LogLevel = CONSOLE_BRIDGE_LOG_DEBUG

CONSOLE_BRIDGE_LOG_INFO module-attribute

Python
CONSOLE_BRIDGE_LOG_INFO: LogLevel = CONSOLE_BRIDGE_LOG_INFO

CONSOLE_BRIDGE_LOG_WARN module-attribute

Python
CONSOLE_BRIDGE_LOG_WARN: LogLevel = CONSOLE_BRIDGE_LOG_WARN

CONSOLE_BRIDGE_LOG_ERROR module-attribute

Python
CONSOLE_BRIDGE_LOG_ERROR: LogLevel = CONSOLE_BRIDGE_LOG_ERROR

CONSOLE_BRIDGE_LOG_NONE module-attribute

Python
CONSOLE_BRIDGE_LOG_NONE: LogLevel = CONSOLE_BRIDGE_LOG_NONE

Isometry3d

Identity staticmethod

Python
Identity() -> Isometry3d

matrix

Python
matrix() -> Annotated[NDArray[numpy.float64], dict(shape=(4, 4), order=F)]

translation

Python
translation() -> Annotated[NDArray[numpy.float64], dict(shape=3, order=C)]

rotation

Python
rotation() -> Annotated[NDArray[numpy.float64], dict(shape=(3, 3), order=F)]

linear

Python
linear() -> Annotated[NDArray[numpy.float64], dict(shape=(3, 3), order=F)]

inverse

Python
inverse() -> Isometry3d

Translation3d

__init__

Python
__init__(arg0: float, arg1: float, arg2: float) -> None

Quaterniond

w

Python
w() -> float

x

Python
x() -> float

y

Python
y() -> float

z

Python
z() -> float

toRotationMatrix

Python
toRotationMatrix() -> Annotated[NDArray[numpy.float64], dict(shape=(3, 3), order=F)]

AngleAxisd

__init__

Python
__init__(arg0: float, arg1: Annotated[NDArray[float64], dict(shape=3, order=C)]) -> None

toRotationMatrix

Python
toRotationMatrix() -> Annotated[NDArray[numpy.float64], dict(shape=(3, 3), order=F)]

FilesystemPath

string

Python
string() -> str

__str__

Python
__str__() -> str

__repr__

Python
__repr__() -> str

Resource

isFile

Python
isFile() -> bool

getUrl

Python
getUrl() -> str

getFilePath

Python
getFilePath() -> str

getResourceContents

Python
getResourceContents() -> bytes

getResourceContentStream

Python
getResourceContentStream() -> 'std::__1::basic_istream<char, std::__1::char_traits<char>>'

BytesResource

Bases: Resource

SimpleLocatedResource

Bases: Resource

ResourceLocator

__init__

Python
__init__() -> None

locateResource

Python
locateResource(arg: str) -> Resource

GeneralResourceLocator

Bases: ResourceLocator

__init__

Python
__init__() -> None

ManipulatorInfo

manipulator property writable

Python
manipulator: str

manipulator_ik_solver property writable

Python
manipulator_ik_solver: str

working_frame property writable

Python
working_frame: str

tcp_frame property writable

Python
tcp_frame: str

tcp_offset property writable

Python
tcp_offset: object

__init__

Python
__init__() -> None

__repr__

Python
__repr__() -> str

JointState

joint_names property writable

Python
joint_names: list[str]

position property writable

Python
position: Annotated[NDArray[float64], dict(shape=(None,), order=C)]

velocity property writable

Python
velocity: Annotated[NDArray[float64], dict(shape=(None,), order=C)]

acceleration property writable

Python
acceleration: Annotated[NDArray[float64], dict(shape=(None,), order=C)]

effort property writable

Python
effort: Annotated[NDArray[float64], dict(shape=(None,), order=C)]

time property writable

Python
time: float

AllowedCollisionMatrix

__init__

Python
__init__() -> None

addAllowedCollision

Python
addAllowedCollision(arg0: str, arg1: str, arg2: str) -> None

removeAllowedCollision

Python
removeAllowedCollision(arg0: str, arg1: str) -> None

isCollisionAllowed

Python
isCollisionAllowed(arg0: str, arg1: str) -> bool

clearAllowedCollisions

Python
clearAllowedCollisions() -> None

getAllAllowedCollisions

Python
getAllAllowedCollisions() -> dict[tuple[str, str], str]

insertAllowedCollisionMatrix

Python
insertAllowedCollisionMatrix(arg: AllowedCollisionMatrix) -> None

CollisionMarginPairOverrideType

Bases: Enum

NONE class-attribute instance-attribute

Python
NONE = 0

REPLACE class-attribute instance-attribute

Python
REPLACE = 1

MODIFY class-attribute instance-attribute

Python
MODIFY = 2

CollisionMarginPairData

__init__

Python
__init__() -> None

setCollisionMargin

Python
setCollisionMargin(arg0: str, arg1: str, arg2: float) -> None

getCollisionMargin

Python
getCollisionMargin(arg0: str, arg1: str) -> float | None

getCollisionMargins

Python
getCollisionMargins() -> dict[tuple[str, str], float]

empty

Python
empty() -> bool

clear

Python
clear() -> None

CollisionMarginData

getDefaultCollisionMargin

Python
getDefaultCollisionMargin() -> float

setDefaultCollisionMargin

Python
setDefaultCollisionMargin(arg: float) -> None

getCollisionMargin

Python
getCollisionMargin(arg0: str, arg1: str) -> float

setCollisionMargin

Python
setCollisionMargin(arg0: str, arg1: str, arg2: float) -> None

getCollisionMarginPairData

Python
getCollisionMarginPairData() -> CollisionMarginPairData

getMaxCollisionMargin

Python
getMaxCollisionMargin() -> float

getPairCollisionMargin

Python
getPairCollisionMargin(arg0: str, arg1: str) -> float

setPairCollisionMargin

Python
setPairCollisionMargin(arg0: str, arg1: str, arg2: float) -> None

KinematicLimits

joint_limits property writable

Python
joint_limits: Annotated[NDArray[float64], dict(shape=(None, 2), order=F)]

velocity_limits property writable

Python
velocity_limits: Annotated[NDArray[float64], dict(shape=(None, 2), order=F)]

acceleration_limits property writable

Python
acceleration_limits: Annotated[NDArray[float64], dict(shape=(None, 2), order=F)]

__init__

Python
__init__() -> None

PluginInfo

class_name property writable

Python
class_name: str

config property writable

Python
config: 'YAML::Node'

__init__

Python
__init__() -> None

LogLevel

Bases: Enum

CONSOLE_BRIDGE_LOG_DEBUG class-attribute instance-attribute

Python
CONSOLE_BRIDGE_LOG_DEBUG = 0

CONSOLE_BRIDGE_LOG_INFO class-attribute instance-attribute

Python
CONSOLE_BRIDGE_LOG_INFO = 1

CONSOLE_BRIDGE_LOG_WARN class-attribute instance-attribute

Python
CONSOLE_BRIDGE_LOG_WARN = 2

CONSOLE_BRIDGE_LOG_ERROR class-attribute instance-attribute

Python
CONSOLE_BRIDGE_LOG_ERROR = 3

CONSOLE_BRIDGE_LOG_NONE class-attribute instance-attribute

Python
CONSOLE_BRIDGE_LOG_NONE = 4

OutputHandler

__init__

Python
__init__() -> None

log

Python
log(arg0: str, arg1: LogLevel, arg2: str, arg3: int) -> None

VectorVector3d

__init__

Python
__init__() -> None

__len__

Python
__len__() -> int

__getitem__

Python
__getitem__(arg: int) -> Annotated[NDArray[numpy.float64], dict(shape=3, order=C)]

__setitem__

Python
__setitem__(arg0: int, arg1: Annotated[NDArray[float64], dict(shape=3, order=C)]) -> None

append

Python
append(arg: Annotated[NDArray[float64], dict(shape=3, order=C)]) -> None

clear

Python
clear() -> None

VectorIsometry3d

__init__

Python
__init__() -> None

__len__

Python
__len__() -> int

__getitem__

Python
__getitem__(arg: int) -> Isometry3d

append

Python
append(arg: Isometry3d) -> None

clear

Python
clear() -> None

setLogLevel

Python
setLogLevel(level: LogLevel) -> None

getLogLevel

Python
getLogLevel() -> LogLevel

log

Python
log(filename: str, line: int, level: LogLevel, msg: str) -> None

useOutputHandler

Python
useOutputHandler(handler: OutputHandler) -> None

restorePreviousOutputHandler

Python
restorePreviousOutputHandler() -> None