Skip to content

tesseract_robotics.trajopt_ifopt

Constraints, costs, and variables for the low-level SQP solver. See the Low-Level SQP guide for the user-guide walkthrough.

Variables (0.34+)

The JointPosition class from 0.33 is removed. Variables now use a three-level hierarchy.

Var

A single variable — typically one joint value at one waypoint.

Node

Groups multiple Vars per waypoint (e.g., joints + velocities at one waypoint).

NodesVariables

Container of Nodes. Passed to IfoptProblem.

createNodesVariables

Factory helper. Builds the full hierarchy from a list of initial states.

Python
from tesseract_robotics.trajopt_ifopt import Bounds, createNodesVariables

bounds = Bounds(-3.14, 3.14)
nodes_variables = createNodesVariables(
    "trajectory", joint_names, initial_states, bounds
)

# Iterate waypoints to pull Var refs for constraints
vars_list = [node.getVar("joints") for node in nodes_variables.getNodes()]

Constraints

Class Purpose
JointPosConstraint Target joint values at a waypoint
JointVelConstraint Velocity limits across consecutive waypoints
JointAccelConstraint Acceleration limits
JointJerkConstraint Jerk limits
CartPosConstraint TCP pose at a waypoint
CartLineConstraint TCP on a line segment between two poses
DiscreteCollisionConstraint Collision at a single waypoint
DiscreteCollisionNumericalConstraint Alternative collision jacobian (numerical)
ContinuousCollisionConstraint Collision between two consecutive waypoints
InverseKinematicsConstraint IK-based constraint

0.34 constraint constructors take Var references directly (not JointPosition lists). See changes for the migration details.

Collision Evaluators

Class Pairs with
SingleTimestepCollisionEvaluator DiscreteCollisionConstraint
LVSDiscreteCollisionEvaluator ContinuousCollisionConstraint (LVS discrete mode)
LVSContinuousCollisionEvaluator ContinuousCollisionConstraint (LVS continuous mode)
DiscreteCollisionEvaluator Base class
ContinuousCollisionEvaluator Base class

CollisionCache was removed in 0.34 — caching is internal to each evaluator.

Info Structs (for Cartesian / IK constraints)

Struct Used by
CartLineInfo CartLineConstraint
InverseKinematicsInfo InverseKinematicsConstraint

CartPosInfo from 0.33 is gone — CartPosConstraint now takes parameters directly (see changes).

Config / Bounds

  • TrajOptCollisionConfig(margin, coeff) — re-exported here and from tesseract_motion_planners_trajopt.
  • CollisionCoeffData — per-pair collision coefficient data.
  • Bounds(lower, upper) — single-variable bounds.
  • Enums: BoundsType, RangeBoundHandling.

Utilities

  • interpolate(start, end, steps) — linear joint interpolation.
  • toBounds(joint_limits) — convert a limits matrix into a Bounds list.

Module API

tesseract_robotics.trajopt_ifopt

__all__ module-attribute

Python
__all__ = ['Var', 'Node', 'NodesVariables', 'BoundsType', 'RangeBoundHandling', 'CartPosConstraint', 'JointPosConstraint', 'JointVelConstraint', 'JointAccelConstraint', 'CollisionCoeffData', 'TrajOptCollisionConfig', 'DiscreteCollisionEvaluator', 'SingleTimestepCollisionEvaluator', 'DiscreteCollisionConstraint', 'interpolate', 'toBounds']

BoundsType

Bases: Enum

UNBOUNDED class-attribute instance-attribute
Python
UNBOUNDED = 0
EQUALITY class-attribute instance-attribute
Python
EQUALITY = 1
LOWER_BOUND class-attribute instance-attribute
Python
LOWER_BOUND = 2
UPPER_BOUND class-attribute instance-attribute
Python
UPPER_BOUND = 3
RANGE_BOUND class-attribute instance-attribute
Python
RANGE_BOUND = 4

RangeBoundHandling

Bases: Enum

KEEP_AS_IS class-attribute instance-attribute
Python
KEEP_AS_IS = 0
SPLIT_TO_TWO_INEQUALITIES class-attribute instance-attribute
Python
SPLIT_TO_TWO_INEQUALITIES = 1

Bounds

__init__
Python
__init__(lower: float = 0.0, upper: float = 0.0) -> None

Create bounds with lower and upper limits

set
Python
set(lower: float, upper: float) -> None

Set both lower and upper bounds

setLower
Python
setLower(lower: float) -> None

Set the lower bound

getLower
Python
getLower() -> float

Get the lower bound value

setUpper
Python
setUpper(upper: float) -> None

Set the upper bound

getUpper
Python
getUpper() -> float

Get the upper bound value

getType
Python
getType() -> BoundsType

Get the cached bound classification

Component

getName
Python
getName() -> str

Get the component name

getRows
Python
getRows() -> int

Get the number of rows

Variables

Bases: Component

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

Get the current variable values

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

Set the variable values from a flat decision vector

getBounds
Python
getBounds() -> list[Bounds]

Get the variable bounds

getHash
Python
getHash() -> int

Get the variable hash for caching

Differentiable

Bases: Component

isDynamic
Python
isDynamic() -> bool

Whether this component can change its number of rows

isScalar
Python
isScalar() -> bool

Whether this component is scalar or stacked

getNonZeros
Python
getNonZeros() -> int

Estimated number of non-zero entries in the Jacobian

update
Python
update() -> int

Recompute sizing/state for dynamic-sized components

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

Get the coefficient vector

ConstraintSet

Bases: Differentiable

__init__
Python
__init__(name: str, n_constraints: int) -> None

Create a constraint set with name and number of constraints

linkWithVariables
Python
linkWithVariables(x: Variables) -> None

Connect the constraint with the optimization variables

getVariables
Python
getVariables() -> Variables

Get the linked optimization variables (protected in C++, exposed via trampoline)

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

Get the current constraint values

getBounds
Python
getBounds() -> list[Bounds]

Get the constraint bounds

getJacobian
Python
getJacobian() -> scipy.sparse.csr_matrix

Get the constraint Jacobian (sparse matrix)

Var

getIdentifier
Python
getIdentifier() -> str

Get the identifier for the variable segment

getIndex
Python
getIndex() -> int

Get the starting index of this variable segment

size
Python
size() -> int

Get the number of elements in this variable segment

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

Get the current variable values

name
Python
name() -> list[str]

Get the variable names

bounds
Python
bounds() -> list[Bounds]

Get the variable bounds

setVariables
Python
setVariables(x: Annotated[NDArray[float64], dict(shape=(None,), writable=False)]) -> None

Set the variable values from the full decision vector

Node

__init__
Python
__init__(node_name: str = 'Node') -> None

Create a node with an optional name

getName
Python
getName() -> str

Get the name of this node

hasVar
Python
hasVar(name: str) -> bool

Check whether this node has a variable by name

getVar
Python
getVar(name: str) -> Var

Get a variable by name

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

Get all variable values as a single vector

getBounds
Python
getBounds() -> list[Bounds]

Get all variable bounds

size
Python
size() -> int

Get total number of scalar decision variables

setVariables
Python
setVariables(x: Annotated[NDArray[float64], dict(shape=(None,), writable=False)]) -> None

Update all variable values from the full decision vector

NodesVariables

Bases: Variables

getNode
Python
getNode(opt_idx: int) -> Node

Get node based on index

getNodes
Python
getNodes() -> list[Node]

Get all nodes

getDim
Python
getDim() -> int

Get the dimensions of every node

CartPosConstraint

Bases: ConstraintSet

use_numeric_differentiation property writable
Python
use_numeric_differentiation: bool

If true, use numeric differentiation (default: true)

__init__
Python
__init__(position_var: Var, manip: 'tesseract_kinematics::JointGroup', source_frame: str, target_frame: str, source_frame_offset: 'Eigen::Transform<double, 3, 1, 0>', target_frame_offset: 'Eigen::Transform<double, 3, 1, 0>', name: str = 'CartPos', range_bound_handling: RangeBoundHandling = RangeBoundHandling.SPLIT_TO_TWO_INEQUALITIES) -> None

Create Cartesian position constraint

calcValues
Python
calcValues(joint_vals: Annotated[NDArray[float64], dict(shape=(None,), writable=False)]) -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]

Calculate error values for given joint values

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

Get current constraint values

setTargetPose
Python
setTargetPose(target_frame_offset: 'Eigen::Transform<double, 3, 1, 0>') -> None

Set the target pose - critical for online planning!

getTargetPose
Python
getTargetPose() -> 'Eigen::Transform<double, 3, 1, 0>'

Get the target pose for the constraint

getCurrentPose
Python
getCurrentPose() -> 'Eigen::Transform<double, 3, 1, 0>'

Get current TCP pose in world frame

JointPosConstraint

Bases: ConstraintSet

__init__
Python
__init__(target: Annotated[NDArray[float64], dict(shape=(None,), order=C)], position_var: Var, coeffs: Annotated[NDArray[float64], dict(shape=(None,), order=C)], name: str = 'JointPos', range_bound_handling: RangeBoundHandling = RangeBoundHandling.SPLIT_TO_TWO_INEQUALITIES) -> None

Create joint position constraint with target values

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

Get current constraint values

JointVelConstraint

Bases: ConstraintSet

__init__
Python
__init__(targets: Annotated[NDArray[float64], dict(shape=(None,), order=C)], position_vars: Sequence[Var], coeffs: Annotated[NDArray[float64], dict(shape=(None,), order=C)], name: str = 'JointVel') -> None

Create joint velocity constraint with target values

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

Get current constraint values

JointAccelConstraint

Bases: ConstraintSet

__init__
Python
__init__(targets: Annotated[NDArray[float64], dict(shape=(None,), order=C)], position_vars: Sequence[Var], coeffs: Annotated[NDArray[float64], dict(shape=(None,), order=C)], name: str = 'JointAccel') -> None

Create joint acceleration constraint with target values

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

Get current constraint values

CollisionCoeffData

setDefaultCollisionCoeff
Python
setDefaultCollisionCoeff(arg: float) -> None
getDefaultCollisionCoeff
Python
getDefaultCollisionCoeff() -> float
setCollisionCoeff
Python
setCollisionCoeff(obj1: str, obj2: str, collision_coeff: float) -> None
getCollisionCoeff
Python
getCollisionCoeff(obj1: str, obj2: str) -> float
setPairCollisionCoeff
Python
setPairCollisionCoeff(obj1: str, obj2: str, collision_coeff: float) -> None
getPairCollisionCoeff
Python
getPairCollisionCoeff(obj1: str, obj2: str) -> float

TrajOptCollisionConfig

enabled property writable
Python
enabled: bool
contact_manager_config property writable
Python
contact_manager_config: ContactManagerConfig
collision_check_config property writable
Python
collision_check_config: CollisionCheckConfig
collision_coeff_data property writable
Python
collision_coeff_data: CollisionCoeffData
collision_margin_buffer property writable
Python
collision_margin_buffer: float
max_num_cnt property writable
Python
max_num_cnt: int

DiscreteCollisionEvaluator

getCollisionMarginBuffer
Python
getCollisionMarginBuffer() -> float
getCollisionMarginData
Python
getCollisionMarginData() -> 'tesseract_common::CollisionMarginData'
getCollisionCoeffData
Python
getCollisionCoeffData() -> CollisionCoeffData

SingleTimestepCollisionEvaluator

Bases: DiscreteCollisionEvaluator

__init__
Python
__init__(manip: 'tesseract_kinematics::JointGroup', env: 'tesseract_environment::Environment', collision_config: TrajOptCollisionConfig, dynamic_environment: bool = False) -> None

DiscreteCollisionConstraint

Bases: ConstraintSet

__init__
Python
__init__(collision_evaluator: DiscreteCollisionEvaluator, position_var: Var, max_num_cnt: int = 1, fixed_sparsity: bool = False, name: str = 'DiscreteCollision') -> None
getValues
Python
getValues() -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]
getCollisionEvaluator
Python
getCollisionEvaluator() -> DiscreteCollisionEvaluator

ContinuousCollisionEvaluator

getCollisionMarginBuffer
Python
getCollisionMarginBuffer() -> float
getCollisionMarginData
Python
getCollisionMarginData() -> 'tesseract_common::CollisionMarginData'
getCollisionCoeffData
Python
getCollisionCoeffData() -> CollisionCoeffData

LVSDiscreteCollisionEvaluator

Bases: ContinuousCollisionEvaluator

__init__
Python
__init__(manip: 'tesseract_kinematics::JointGroup', env: 'tesseract_environment::Environment', collision_config: TrajOptCollisionConfig, dynamic_environment: bool = False) -> None

LVSContinuousCollisionEvaluator

Bases: ContinuousCollisionEvaluator

__init__
Python
__init__(manip: 'tesseract_kinematics::JointGroup', env: 'tesseract_environment::Environment', collision_config: TrajOptCollisionConfig, dynamic_environment: bool = False) -> None

ContinuousCollisionConstraint

Bases: ConstraintSet

__init__
Python
__init__(collision_evaluator: ContinuousCollisionEvaluator, position_var0: Var, position_var1: Var, fixed0: bool = False, fixed1: bool = False, max_num_cnt: int = 1, fixed_sparsity: bool = False, name: str = 'LVSCollision') -> None
getValues
Python
getValues() -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]
getCollisionEvaluator
Python
getCollisionEvaluator() -> ContinuousCollisionEvaluator

JointJerkConstraint

Bases: ConstraintSet

__init__
Python
__init__(targets: Annotated[NDArray[float64], dict(shape=(None,), order=C)], position_vars: Sequence[Var], coeffs: Annotated[NDArray[float64], dict(shape=(None,), order=C)], name: str = 'JointJerk') -> None

Create joint jerk constraint (requires 4+ consecutive waypoints)

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

Get current constraint values

CartLineInfo

manip property writable
Python
manip: 'tesseract_kinematics::JointGroup'

The joint group

source_frame property writable
Python
source_frame: str

TCP frame

target_frame property writable
Python
target_frame: str

Reference frame

source_frame_offset property writable
Python
source_frame_offset: 'Eigen::Transform<double, 3, 1, 0>'

TCP offset

target_frame_offset1 property writable
Python
target_frame_offset1: 'Eigen::Transform<double, 3, 1, 0>'

Line start pose

target_frame_offset2 property writable
Python
target_frame_offset2: 'Eigen::Transform<double, 3, 1, 0>'

Line end pose

indices property writable
Python
indices: Annotated[NDArray[int32], dict(shape=(None,), order=C)]

DOF indices to constrain: default {0,1,2,3,4,5}

__init__
Python
__init__() -> None

CartLineConstraint

Bases: ConstraintSet

use_numeric_differentiation property writable
Python
use_numeric_differentiation: bool

If true, use numeric differentiation (default: true)

__init__
Python
__init__(info: CartLineInfo, position_var: Var, coeffs: Annotated[NDArray[float64], dict(shape=(None,), order=C)], name: str = 'CartLine') -> None

Create Cartesian line constraint

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

Get current constraint values

calcValues
Python
calcValues(joint_vals: Annotated[NDArray[float64], dict(shape=(None,), writable=False)]) -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]

Calculate error values for given joint values

getLinePoint
Python
getLinePoint(source_tf: 'Eigen::Transform<double, 3, 1, 0>', target_tf1: 'Eigen::Transform<double, 3, 1, 0>', target_tf2: 'Eigen::Transform<double, 3, 1, 0>') -> 'Eigen::Transform<double, 3, 1, 0>'

Find nearest point on line (uses SLERP for orientation)

DiscreteCollisionNumericalConstraint

Bases: ConstraintSet

__init__
Python
__init__(collision_evaluator: DiscreteCollisionEvaluator, position_var: Var, max_num_cnt: int = 1, fixed_sparsity: bool = False, name: str = 'DiscreteCollisionNumerical') -> None

Create discrete collision constraint with numerical jacobians

getValues
Python
getValues() -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]
calcValues
Python
calcValues(joint_vals: Annotated[NDArray[float64], dict(shape=(None,), writable=False)]) -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]
getCollisionEvaluator
Python
getCollisionEvaluator() -> DiscreteCollisionEvaluator

InverseKinematicsInfo

manip property writable
Python
manip: 'tesseract_kinematics::KinematicGroup'

The kinematic group (with IK solver)

working_frame property writable
Python
working_frame: str

Working frame (not currently used)

tcp_frame property writable
Python
tcp_frame: str

TCP frame (not currently used)

tcp_offset property writable
Python
tcp_offset: 'Eigen::Transform<double, 3, 1, 0>'

TCP offset (not currently used)

__init__
Python
__init__() -> None

InverseKinematicsConstraint

Bases: ConstraintSet

__init__
Python
__init__(target_pose: 'Eigen::Transform<double, 3, 1, 0>', kinematic_info: InverseKinematicsInfo, constraint_var: Var, seed_var: Var, name: str = 'InverseKinematics') -> None

Create IK constraint (constraint_var constrained to IK solution seeded from seed_var)

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

Get current constraint values

createNodesVariables

Python
createNodesVariables(variable_name: str, joint_names: Sequence[str], initial_values: Sequence[Annotated[NDArray[float64], dict(shape=(None,), order=C)]], bounds: Sequence[Bounds]) -> NodesVariables

Create NodesVariables with one vector Var per node.

Parameters:

Name Type Description Default
variable_name str

Name for the variable set

required
joint_names Sequence[str]

Joint name for each DOF

required
initial_values Sequence[Annotated[NDArray[float64], dict(shape=(None,), order=C)]]

List of initial joint value vectors (one per waypoint)

required
bounds Sequence[Bounds]

Joint bounds (shared across all waypoints)

required

interpolate

Python
interpolate(start: Annotated[NDArray[float64], dict(shape=(None,), writable=False)], end: Annotated[NDArray[float64], dict(shape=(None,), writable=False)], steps: int) -> list[Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]]

Interpolate between two joint vectors, returning 'steps' waypoints

See also