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.
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 fromtesseract_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 aBoundslist.
Module API¶
tesseract_robotics.trajopt_ifopt
¶
__all__
module-attribute
¶
__all__ = ['Var', 'Node', 'NodesVariables', 'BoundsType', 'RangeBoundHandling', 'CartPosConstraint', 'JointPosConstraint', 'JointVelConstraint', 'JointAccelConstraint', 'CollisionCoeffData', 'TrajOptCollisionConfig', 'DiscreteCollisionEvaluator', 'SingleTimestepCollisionEvaluator', 'DiscreteCollisionConstraint', 'interpolate', 'toBounds']
BoundsType
¶
Bases: Enum
RangeBoundHandling
¶
Component
¶
Variables
¶
ConstraintSet
¶
Bases: Differentiable
__init__
¶
Create a constraint set with name and number of constraints
linkWithVariables
¶
Connect the constraint with the optimization variables
getVariables
¶
Get the linked optimization variables (protected in C++, exposed via trampoline)
getValues
¶
Get the current constraint values
getJacobian
¶
Get the constraint Jacobian (sparse matrix)
Var
¶
Node
¶
NodesVariables
¶
CartPosConstraint
¶
Bases: ConstraintSet
use_numeric_differentiation
property
writable
¶
If true, use numeric differentiation (default: true)
__init__
¶
__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
¶
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
¶
Get current constraint values
setTargetPose
¶
Set the target pose - critical for online planning!
getTargetPose
¶
Get the target pose for the constraint
getCurrentPose
¶
Get current TCP pose in world frame
JointPosConstraint
¶
Bases: ConstraintSet
__init__
¶
__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
¶
Get current constraint values
JointVelConstraint
¶
Bases: ConstraintSet
__init__
¶
__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
¶
Get current constraint values
JointAccelConstraint
¶
Bases: ConstraintSet
__init__
¶
__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
¶
Get current constraint values
TrajOptCollisionConfig
¶
DiscreteCollisionEvaluator
¶
SingleTimestepCollisionEvaluator
¶
Bases: DiscreteCollisionEvaluator
__init__
¶
__init__(manip: 'tesseract_kinematics::JointGroup', env: 'tesseract_environment::Environment', collision_config: TrajOptCollisionConfig, dynamic_environment: bool = False) -> None
DiscreteCollisionConstraint
¶
Bases: ConstraintSet
__init__
¶
__init__(collision_evaluator: DiscreteCollisionEvaluator, position_var: Var, max_num_cnt: int = 1, fixed_sparsity: bool = False, name: str = 'DiscreteCollision') -> None
ContinuousCollisionEvaluator
¶
LVSDiscreteCollisionEvaluator
¶
Bases: ContinuousCollisionEvaluator
__init__
¶
__init__(manip: 'tesseract_kinematics::JointGroup', env: 'tesseract_environment::Environment', collision_config: TrajOptCollisionConfig, dynamic_environment: bool = False) -> None
LVSContinuousCollisionEvaluator
¶
Bases: ContinuousCollisionEvaluator
__init__
¶
__init__(manip: 'tesseract_kinematics::JointGroup', env: 'tesseract_environment::Environment', collision_config: TrajOptCollisionConfig, dynamic_environment: bool = False) -> None
ContinuousCollisionConstraint
¶
Bases: ConstraintSet
__init__
¶
__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
JointJerkConstraint
¶
Bases: ConstraintSet
__init__
¶
__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
¶
Get current constraint values
CartLineInfo
¶
CartLineConstraint
¶
Bases: ConstraintSet
use_numeric_differentiation
property
writable
¶
If true, use numeric differentiation (default: true)
__init__
¶
__init__(info: CartLineInfo, position_var: Var, coeffs: Annotated[NDArray[float64], dict(shape=(None,), order=C)], name: str = 'CartLine') -> None
Create Cartesian line constraint
getValues
¶
Get current constraint values
calcValues
¶
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
¶
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__
¶
__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
calcValues
¶
calcValues(joint_vals: Annotated[NDArray[float64], dict(shape=(None,), writable=False)]) -> Annotated[NDArray[numpy.float64], dict(shape=(None,), order=C)]
InverseKinematicsInfo
¶
InverseKinematicsConstraint
¶
Bases: ConstraintSet
__init__
¶
__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
¶
Get current constraint values
createNodesVariables
¶
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
¶
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¶
- Low-Level SQP API — user-guide walkthrough
- 0.33 → 0.34 migration — if you're porting from the old
ifoptmodule