Skip to content

tesseract_robotics.tesseract_command_language

Motion program instructions and waypoints.

Overview

The command language defines motion tasks as a tree of instructions:

Text Only
CompositeInstruction (program)
├── MoveInstruction (freespace to via point)
├── MoveInstruction (linear to target)
└── CompositeInstruction (sub-program)
    ├── MoveInstruction
    └── MoveInstruction

Waypoints

StateWaypoint

Joint-space target (specific joint values).

Python
from tesseract_robotics.tesseract_command_language import (
    StateWaypoint, StateWaypointPoly, StateWaypointPoly_wrap_StateWaypoint
)
import numpy as np

joint_names = ["joint_1", "joint_2", "joint_3", "joint_4", "joint_5", "joint_6"]
joint_values = np.array([0.0, -0.5, 0.5, 0.0, 0.5, 0.0])

# Create waypoint
wp = StateWaypoint(joint_names, joint_values)

# Wrap in polymorphic type (required for instructions)
wp_poly = StateWaypointPoly_wrap_StateWaypoint(wp)

# Access values
print(f"Names: {wp.getNames()}")
print(f"Position: {wp.getPosition()}")

CartesianWaypoint

Cartesian-space target (pose).

Python
from tesseract_robotics.tesseract_command_language import (
    CartesianWaypoint, CartesianWaypointPoly, CartesianWaypointPoly_wrap_CartesianWaypoint
)
from tesseract_robotics.tesseract_common import Isometry3d
import numpy as np

# Create target pose (build the 4x4 matrix then wrap)
mat = np.eye(4)
mat[:3, 3] = [0.5, 0.2, 0.3]
pose = Isometry3d(mat)

# Create waypoint
wp = CartesianWaypoint(pose)

# With seed (initial joint guess for IK)
wp = CartesianWaypoint(pose)
wp.setSeed(seed_state)  # StateWaypointPoly

# Wrap in polymorphic type
wp_poly = CartesianWaypointPoly_wrap_CartesianWaypoint(wp)

JointWaypoint

Named joint positions (subset of joints).

Python
from tesseract_robotics.tesseract_command_language import (
    JointWaypoint, JointWaypointPoly, JointWaypointPoly_wrap_JointWaypoint
)

names = ["joint_1", "joint_3"]
values = np.array([0.5, -0.5])

wp = JointWaypoint(names, values)
wp_poly = JointWaypointPoly_wrap_JointWaypoint(wp)

Instructions

MoveInstruction

Single motion command.

Python
from tesseract_robotics.tesseract_command_language import (
    MoveInstruction, MoveInstructionPoly, MoveInstructionPoly_wrap_MoveInstruction,
    MoveInstructionType
)

# Create move instruction
instr = MoveInstruction(wp_poly, MoveInstructionType.FREESPACE, "DEFAULT")

# With specific profile
instr = MoveInstruction(wp_poly, MoveInstructionType.LINEAR, "my_profile")

# Wrap in polymorphic type
instr_poly = MoveInstructionPoly_wrap_MoveInstruction(instr)

# Access properties
print(f"Profile: {instr.getProfile()}")
print(f"Type: {instr.getMoveType()}")
waypoint = instr.getWaypoint()

MoveInstructionType

Type Description Typical Planner
FREESPACE Any collision-free path OMPL
LINEAR Straight Cartesian line TrajOpt
CIRCULAR Circular arc Specialized

CompositeInstruction

Container for multiple instructions.

Python
from tesseract_robotics.tesseract_command_language import (
    CompositeInstruction, CompositeInstructionOrder
)

# Create program
program = CompositeInstruction("DEFAULT")

# Set manipulator info
from tesseract_robotics.tesseract_common import ManipulatorInfo
manip_info = ManipulatorInfo()
manip_info.manipulator = "manipulator"
manip_info.tcp_frame = "tool0"
manip_info.working_frame = "base_link"
program.setManipulatorInfo(manip_info)

# Add instructions
program.appendMoveInstruction(move1)
program.appendMoveInstruction(move2)

# push_back accepts either a single Instruction or a nested CompositeInstruction
# (0.35+) so raster-style programs can be built the same way they are in C++:
program.push_back(sub_composite)

# Iterate instructions
for instr in program.getInstructions():
    pass

CompositeInstructionOrder

Order Description
ORDERED Execute in sequence
UNORDERED Can be reordered
ORDERED_AND_REVERTED Sequence, can reverse

Non-Motion Instructions

Programs can also contain non-motion instructions: timed waits, IO handshakes, analog/digital setpoint changes, and tool changes. These are typically passed through the planning pipeline unchanged and acted on at runtime by the trajectory executor.

Concrete instruction types (WaitInstruction, TimerInstruction, SetAnalogInstruction, SetDigitalInstruction, SetToolInstruction) can be pushed directly into a CompositeInstruction via push_back — implicit conversion to InstructionPoly is registered so no explicit wrap is needed.

WaitInstruction

Pause execution for a fixed duration or until an IO line transitions.

Python
from tesseract_robotics.tesseract_command_language import (
    WaitInstruction, WaitInstructionType,
)

# Time-based wait
program.push_back(WaitInstruction(0.5))  # wait 0.5 seconds

# IO handshake — wait until digital input 3 goes high
program.push_back(WaitInstruction(WaitInstructionType.DIGITAL_INPUT_HIGH, 3))
WaitInstructionType Behaviour
TIME Wait time seconds
DIGITAL_INPUT_HIGH / DIGITAL_INPUT_LOW Block until input io is high / low
DIGITAL_OUTPUT_HIGH / DIGITAL_OUTPUT_LOW Block until output io is high / low

TimerInstruction

Start a timer that, on expiry, drives a digital output high or low.

Python
from tesseract_robotics.tesseract_command_language import (
    TimerInstruction, TimerInstructionType,
)

program.push_back(
    TimerInstruction(TimerInstructionType.DIGITAL_OUTPUT_HIGH, 2.0, 4)
)

SetAnalogInstruction / SetDigitalInstruction

Drive an analog or digital channel.

Python
from tesseract_robotics.tesseract_command_language import (
    SetAnalogInstruction, SetDigitalInstruction,
)

# Analog: set channel ("speed", index 1) to 0.75
program.push_back(SetAnalogInstruction("speed", 1, 0.75))

# Digital: open the gripper
program.push_back(SetDigitalInstruction("gripper", 2, True))

SetToolInstruction

Activate a tool by ID.

Python
from tesseract_robotics.tesseract_command_language import SetToolInstruction

program.push_back(SetToolInstruction(5))

Iteration and dispatch

When iterating a CompositeInstruction, each child is an InstructionPoly. Use the is*Instruction predicates to dispatch and as*Instruction to obtain the concrete value.

Python
for i in range(len(program)):
    child = program[i]
    if child.isMoveInstruction():
        mi = child.asMoveInstruction()
    elif child.isWaitInstruction():
        wi = child.asWaitInstruction()
    elif child.isTimerInstruction():
        ti = child.asTimerInstruction()
    elif child.isSetAnalogInstruction():
        si = child.asSetAnalogInstruction()
    elif child.isSetDigitalInstruction():
        si = child.asSetDigitalInstruction()
    elif child.isSetToolInstruction():
        si = child.asSetToolInstruction()
    elif child.isCompositeInstruction():
        sub = child.asCompositeInstruction()

as*Instruction raises RuntimeError if the underlying type does not match — always guard with the matching is*Instruction predicate.

Profiles

ProfileDictionary

Container for planner profiles.

Python
from tesseract_robotics.tesseract_command_language import (
    ProfileDictionary, ProfileDictionary_addProfile
)

profiles = ProfileDictionary()

# Add profiles (type-specific functions)
from tesseract_robotics.tesseract_motion_planners_ompl import (
    ProfileDictionary_addOMPLProfile
)
ProfileDictionary_addOMPLProfile(profiles, "DEFAULT", ompl_profile)

Type Erasure Helpers

The command language uses type erasure. Use these functions to wrap/unwrap types:

Wrapping (concrete → polymorphic)

Python
# Waypoints
StateWaypointPoly_wrap_StateWaypoint(wp)
CartesianWaypointPoly_wrap_CartesianWaypoint(wp)
JointWaypointPoly_wrap_JointWaypoint(wp)

# Instructions
MoveInstructionPoly_wrap_MoveInstruction(instr)

# AnyPoly (for data storage)
AnyPoly_wrap_CompositeInstruction(program)
AnyPoly_wrap_ProfileDictionary(profiles)

CompositeInstruction.push_back accepts any concrete instruction type (MoveInstructionPoly, CompositeInstruction, WaitInstruction, TimerInstruction, SetAnalogInstruction, SetDigitalInstruction, SetToolInstruction) directly — implicit conversion to InstructionPoly removes the need for an explicit wrap call.

Unwrapping (polymorphic → concrete)

Python
# Waypoints
WaypointPoly_as_StateWaypointPoly(wp_poly)
WaypointPoly_as_CartesianWaypointPoly(wp_poly)
WaypointPoly_as_JointWaypointPoly(wp_poly)

# Instructions
InstructionPoly_as_MoveInstructionPoly(instr_poly)
InstructionPoly_as_WaitInstruction(instr_poly)
InstructionPoly_as_TimerInstruction(instr_poly)
InstructionPoly_as_SetAnalogInstruction(instr_poly)
InstructionPoly_as_SetDigitalInstruction(instr_poly)
InstructionPoly_as_SetToolInstruction(instr_poly)

# AnyPoly
AnyPoly_as_CompositeInstruction(any_poly)

These free functions mirror the as*Instruction methods on InstructionPoly and raise RuntimeError when the underlying type does not match.

Complete Example

Python
from tesseract_robotics.tesseract_command_language import (
    StateWaypoint, StateWaypointPoly_wrap_StateWaypoint,
    CartesianWaypoint, CartesianWaypointPoly_wrap_CartesianWaypoint,
    MoveInstruction, MoveInstructionType,
    MoveInstructionPoly_wrap_MoveInstruction,
    CompositeInstruction,
)
from tesseract_robotics.tesseract_common import ManipulatorInfo, Isometry3d
import numpy as np

# Setup
joint_names = ["j1", "j2", "j3", "j4", "j5", "j6"]
start_joints = np.zeros(6)

goal_mat = np.eye(4)
goal_mat[:3, 3] = [0.5, 0.2, 0.3]
goal_pose = Isometry3d(goal_mat)

# Create waypoints
start_wp = StateWaypointPoly_wrap_StateWaypoint(
    StateWaypoint(joint_names, start_joints)
)
goal_wp = CartesianWaypointPoly_wrap_CartesianWaypoint(
    CartesianWaypoint(goal_pose)
)

# Create instructions (wrap in MoveInstructionPoly before appending)
start_instr = MoveInstructionPoly_wrap_MoveInstruction(
    MoveInstruction(start_wp, MoveInstructionType.FREESPACE, "DEFAULT")
)
goal_instr = MoveInstructionPoly_wrap_MoveInstruction(
    MoveInstruction(goal_wp, MoveInstructionType.LINEAR, "DEFAULT")
)

# Create program
program = CompositeInstruction("DEFAULT")

manip_info = ManipulatorInfo()
manip_info.manipulator = "manipulator"
manip_info.tcp_frame = "tool0"
manip_info.working_frame = "base_link"
program.setManipulatorInfo(manip_info)

program.appendMoveInstruction(start_instr)
program.appendMoveInstruction(goal_instr)

# Program is ready for TaskComposer

Auto-generated API Reference

tesseract_command_language Python bindings

DEFAULT_PROFILE_KEY module-attribute

Python
DEFAULT_PROFILE_KEY: str = 'DEFAULT'

MoveInstructionType_LINEAR module-attribute

Python
MoveInstructionType_LINEAR: MoveInstructionType = LINEAR

MoveInstructionType_FREESPACE module-attribute

Python
MoveInstructionType_FREESPACE: MoveInstructionType = FREESPACE

MoveInstructionType_CIRCULAR module-attribute

Python
MoveInstructionType_CIRCULAR: MoveInstructionType = CIRCULAR

JointWaypoint

setNames

Python
setNames(names: Sequence[str]) -> None

getNames

Python
getNames() -> list[str]

setPosition

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

getPosition

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

setUpperTolerance

Python
setUpperTolerance(upper_tol: Annotated[NDArray[float64], dict(shape=(None,), order=C)]) -> None

getUpperTolerance

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

setLowerTolerance

Python
setLowerTolerance(lower_tol: Annotated[NDArray[float64], dict(shape=(None,), order=C)]) -> None

getLowerTolerance

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

setIsConstrained

Python
setIsConstrained(value: bool) -> None

isConstrained

Python
isConstrained() -> bool

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

CartesianWaypoint

setTransform

Python
setTransform(transform: Isometry3d) -> None

getTransform

Python
getTransform() -> tesseract_robotics.tesseract_common._tesseract_common.Isometry3d

setUpperTolerance

Python
setUpperTolerance(upper_tol: Annotated[NDArray[float64], dict(shape=(None,), order=C)]) -> None

getUpperTolerance

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

setLowerTolerance

Python
setLowerTolerance(lower_tol: Annotated[NDArray[float64], dict(shape=(None,), order=C)]) -> None

getLowerTolerance

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

setSeed

Python
setSeed(seed: JointState) -> None

getSeed

Python
getSeed() -> tesseract_robotics.tesseract_common._tesseract_common.JointState

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

StateWaypoint

setNames

Python
setNames(names: Sequence[str]) -> None

getNames

Python
getNames() -> list[str]

setPosition

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

getPosition

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

setVelocity

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

getVelocity

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

setAcceleration

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

getAcceleration

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

setEffort

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

getEffort

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

setTime

Python
setTime(time: float) -> None

getTime

Python
getTime() -> float

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

MoveInstructionType

Bases: Enum

LINEAR class-attribute instance-attribute

Python
LINEAR = 0

FREESPACE class-attribute instance-attribute

Python
FREESPACE = 1

CIRCULAR class-attribute instance-attribute

Python
CIRCULAR = 2

CompositeInstructionOrder

Bases: Enum

ORDERED class-attribute instance-attribute

Python
ORDERED = 0

UNORDERED class-attribute instance-attribute

Python
UNORDERED = 1

ORDERED_AND_REVERABLE class-attribute instance-attribute

Python
ORDERED_AND_REVERABLE = 2

WaypointPoly

__init__

Python
__init__() -> None

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

isCartesianWaypoint

Python
isCartesianWaypoint() -> bool

isJointWaypoint

Python
isJointWaypoint() -> bool

isStateWaypoint

Python
isStateWaypoint() -> bool

isNull

Python
isNull() -> bool

CartesianWaypointPoly

getTransform

Python
getTransform() -> tesseract_robotics.tesseract_common._tesseract_common.Isometry3d

setTransform

Python
setTransform(transform: Isometry3d) -> None

hasSeed

Python
hasSeed() -> bool

clearSeed

Python
clearSeed() -> None

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

isNull

Python
isNull() -> bool

JointWaypointPoly

getNames

Python
getNames() -> list[str]

setNames

Python
setNames(names: Sequence[str]) -> None

getPosition

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

setPosition

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

isConstrained

Python
isConstrained() -> bool

setIsConstrained

Python
setIsConstrained(value: bool) -> None

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

isNull

Python
isNull() -> bool

StateWaypointPoly

getNames

Python
getNames() -> list[str]

setNames

Python
setNames(names: Sequence[str]) -> None

getPosition

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

setPosition

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

getVelocity

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

setVelocity

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

getAcceleration

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

setAcceleration

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

getTime

Python
getTime() -> float

setTime

Python
setTime(time: float) -> None

setName

Python
setName(name: str) -> None

getName

Python
getName() -> str

print

Python
print(prefix: str = '') -> None

isNull

Python
isNull() -> bool

InstructionPoly

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

isCompositeInstruction

Python
isCompositeInstruction() -> bool

isMoveInstruction

Python
isMoveInstruction() -> bool

isWaitInstruction

Python
isWaitInstruction() -> bool

isTimerInstruction

Python
isTimerInstruction() -> bool

isSetAnalogInstruction

Python
isSetAnalogInstruction() -> bool

isSetDigitalInstruction

Python
isSetDigitalInstruction() -> bool

isSetToolInstruction

Python
isSetToolInstruction() -> bool

isNull

Python
isNull() -> bool

asMoveInstruction

Python
asMoveInstruction() -> MoveInstructionPoly

Cast to MoveInstructionPoly. Raises RuntimeError if not a move instruction.

asCompositeInstruction

Python
asCompositeInstruction() -> CompositeInstruction

Cast to CompositeInstruction. Raises RuntimeError if not a composite instruction.

asWaitInstruction

Python
asWaitInstruction() -> WaitInstruction

Cast to WaitInstruction. Raises RuntimeError if not a wait instruction.

asTimerInstruction

Python
asTimerInstruction() -> TimerInstruction

Cast to TimerInstruction. Raises RuntimeError if not a timer instruction.

asSetAnalogInstruction

Python
asSetAnalogInstruction() -> SetAnalogInstruction

Cast to SetAnalogInstruction. Raises RuntimeError if not a set analog instruction.

asSetDigitalInstruction

Python
asSetDigitalInstruction() -> SetDigitalInstruction

Cast to SetDigitalInstruction. Raises RuntimeError if not a set digital instruction.

asSetToolInstruction

Python
asSetToolInstruction() -> SetToolInstruction

Cast to SetToolInstruction. Raises RuntimeError if not a set tool instruction.

MoveInstructionPoly

__init__

Python
__init__() -> None

getWaypoint

Python
getWaypoint() -> WaypointPoly

assignCartesianWaypoint

Python
assignCartesianWaypoint(waypoint: CartesianWaypointPoly) -> None

assignJointWaypoint

Python
assignJointWaypoint(waypoint: JointWaypointPoly) -> None

assignStateWaypoint

Python
assignStateWaypoint(waypoint: StateWaypointPoly) -> None

getMoveType

Python
getMoveType() -> MoveInstructionType

setMoveType

Python
setMoveType(move_type: MoveInstructionType) -> None

getProfile

Python
getProfile(ns: str = '') -> str

setProfile

Python
setProfile(profile: str) -> None

getPathProfile

Python
getPathProfile(ns: str = '') -> str

setPathProfile

Python
setPathProfile(profile: str) -> None

getManipulatorInfo

Python
getManipulatorInfo() -> tesseract_robotics.tesseract_common._tesseract_common.ManipulatorInfo

setManipulatorInfo

Python
setManipulatorInfo(info: ManipulatorInfo) -> None

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

isNull

Python
isNull() -> bool

MoveInstruction

getWaypoint

Python
getWaypoint() -> WaypointPoly

assignCartesianWaypoint

Python
assignCartesianWaypoint(waypoint: CartesianWaypointPoly) -> None

assignJointWaypoint

Python
assignJointWaypoint(waypoint: JointWaypointPoly) -> None

assignStateWaypoint

Python
assignStateWaypoint(waypoint: StateWaypointPoly) -> None

getMoveType

Python
getMoveType() -> MoveInstructionType

setMoveType

Python
setMoveType(move_type: MoveInstructionType) -> None

getProfile

Python
getProfile(ns: str = '') -> str

setProfile

Python
setProfile(profile: str) -> None

getPathProfile

Python
getPathProfile(ns: str = '') -> str

setPathProfile

Python
setPathProfile(profile: str) -> None

getManipulatorInfo

Python
getManipulatorInfo() -> tesseract_robotics.tesseract_common._tesseract_common.ManipulatorInfo

setManipulatorInfo

Python
setManipulatorInfo(info: ManipulatorInfo) -> None

print

Python
print(prefix: str = '') -> None

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

WaitInstructionType

Bases: Enum

TIME class-attribute instance-attribute

Python
TIME = 0

DIGITAL_INPUT_HIGH class-attribute instance-attribute

Python
DIGITAL_INPUT_HIGH = 1

DIGITAL_INPUT_LOW class-attribute instance-attribute

Python
DIGITAL_INPUT_LOW = 2

DIGITAL_OUTPUT_HIGH class-attribute instance-attribute

Python
DIGITAL_OUTPUT_HIGH = 3

DIGITAL_OUTPUT_LOW class-attribute instance-attribute

Python
DIGITAL_OUTPUT_LOW = 4

WaitInstruction

getWaitType

Python
getWaitType() -> WaitInstructionType

setWaitType

Python
setWaitType(type: WaitInstructionType) -> None

getWaitTime

Python
getWaitTime() -> float

setWaitTime

Python
setWaitTime(time: float) -> None

getWaitIO

Python
getWaitIO() -> int

setWaitIO

Python
setWaitIO(io: int) -> None

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

TimerInstructionType

Bases: Enum

DIGITAL_OUTPUT_HIGH class-attribute instance-attribute

Python
DIGITAL_OUTPUT_HIGH = 0

DIGITAL_OUTPUT_LOW class-attribute instance-attribute

Python
DIGITAL_OUTPUT_LOW = 1

TimerInstruction

__init__

Python
__init__(type: TimerInstructionType, time: float, io: int) -> None

Construct a timer that, after time seconds, drives digital output io HIGH or LOW per type.

getTimerType

Python
getTimerType() -> TimerInstructionType

setTimerType

Python
setTimerType(type: TimerInstructionType) -> None

getTimerTime

Python
getTimerTime() -> float

setTimerTime

Python
setTimerTime(time: float) -> None

getTimerIO

Python
getTimerIO() -> int

setTimerIO

Python
setTimerIO(io: int) -> None

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

SetAnalogInstruction

__init__

Python
__init__(key: str, index: int, value: float) -> None

Set analog channel identified by (key, index) to value.

getKey

Python
getKey() -> str

getIndex

Python
getIndex() -> int

getValue

Python
getValue() -> float

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

SetDigitalInstruction

__init__

Python
__init__(key: str, index: int, value: bool) -> None

Set digital channel identified by (key, index) to value.

getKey

Python
getKey() -> str

getIndex

Python
getIndex() -> int

getValue

Python
getValue() -> bool

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

SetToolInstruction

__init__

Python
__init__(tool_id: int) -> None

Activate the tool with the given ID.

getTool

Python
getTool() -> int

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

CompositeInstruction

getOrder

Python
getOrder() -> CompositeInstructionOrder

getDescription

Python
getDescription() -> str

setDescription

Python
setDescription(description: str) -> None

print

Python
print(prefix: str = '') -> None

getProfile

Python
getProfile(ns: str = '') -> str

setProfile

Python
setProfile(profile: str) -> None

getManipulatorInfo

Python
getManipulatorInfo() -> tesseract_robotics.tesseract_common._tesseract_common.ManipulatorInfo

setManipulatorInfo

Python
setManipulatorInfo(info: ManipulatorInfo) -> None

getInstructions

Python
getInstructions() -> list[InstructionPoly]

setInstructions

Python
setInstructions(instructions: Sequence[InstructionPoly]) -> None

appendMoveInstruction

Python
appendMoveInstruction(mi: MoveInstructionPoly) -> None

size

Python
size() -> int

empty

Python
empty() -> bool

clear

Python
clear() -> None

__len__

Python
__len__() -> int

__getitem__

Python
__getitem__(arg: int) -> InstructionPoly

__iter__

Python
__iter__() -> Iterator[InstructionPoly]

Profile

getKey

Python
getKey() -> int

ProfileDictionary

__init__

Python
__init__() -> None

addProfile

Python
addProfile(ns: str, profile_name: str, profile: Profile) -> None

hasProfile

Python
hasProfile(key: int, ns: str, profile_name: str) -> bool

getProfile

Python
getProfile(key: int, ns: str, profile_name: str) -> Profile

removeProfile

Python
removeProfile(key: int, ns: str, profile_name: str) -> None

hasProfileEntry

Python
hasProfileEntry(key: int, ns: str) -> bool

removeProfileEntry

Python
removeProfileEntry(key: int, ns: str) -> None

clear

Python
clear() -> None

CartesianWaypointPoly_wrap_CartesianWaypoint

Python
CartesianWaypointPoly_wrap_CartesianWaypoint(waypoint: CartesianWaypoint) -> CartesianWaypointPoly

JointWaypointPoly_wrap_JointWaypoint

Python
JointWaypointPoly_wrap_JointWaypoint(waypoint: JointWaypoint) -> JointWaypointPoly

StateWaypointPoly_wrap_StateWaypoint

Python
StateWaypointPoly_wrap_StateWaypoint(waypoint: StateWaypoint) -> StateWaypointPoly

MoveInstructionPoly_wrap_MoveInstruction

Python
MoveInstructionPoly_wrap_MoveInstruction(instruction: MoveInstruction) -> MoveInstructionPoly

InstructionPoly_as_MoveInstructionPoly

Python
InstructionPoly_as_MoveInstructionPoly(instruction: InstructionPoly) -> MoveInstructionPoly

InstructionPoly_as_CompositeInstruction

Python
InstructionPoly_as_CompositeInstruction(instruction: InstructionPoly) -> CompositeInstruction

InstructionPoly_as_WaitInstruction

Python
InstructionPoly_as_WaitInstruction(instruction: InstructionPoly) -> WaitInstruction

InstructionPoly_as_TimerInstruction

Python
InstructionPoly_as_TimerInstruction(instruction: InstructionPoly) -> TimerInstruction

InstructionPoly_as_SetAnalogInstruction

Python
InstructionPoly_as_SetAnalogInstruction(instruction: InstructionPoly) -> SetAnalogInstruction

InstructionPoly_as_SetDigitalInstruction

Python
InstructionPoly_as_SetDigitalInstruction(instruction: InstructionPoly) -> SetDigitalInstruction

InstructionPoly_as_SetToolInstruction

Python
InstructionPoly_as_SetToolInstruction(instruction: InstructionPoly) -> SetToolInstruction

WaypointPoly_as_StateWaypointPoly

Python
WaypointPoly_as_StateWaypointPoly(waypoint: WaypointPoly) -> StateWaypointPoly

WaypointPoly_as_CartesianWaypointPoly

Python
WaypointPoly_as_CartesianWaypointPoly(waypoint: WaypointPoly) -> CartesianWaypointPoly

WaypointPoly_as_JointWaypointPoly

Python
WaypointPoly_as_JointWaypointPoly(waypoint: WaypointPoly) -> JointWaypointPoly

ProfileDictionary_addProfile

Python
ProfileDictionary_addProfile(dict: ProfileDictionary, ns: str, profile_name: str, profile: Profile) -> None

Add a profile to the dictionary (cross-module helper)