Tasks
EmbodiK supports various task types for multi-task inverse kinematics.
Task Types
FrameTask
Control end-effector pose (position + orientation).
frame_task = embodik.FrameTask(
frame_id="end_effector",
target_pose=np.eye(4) # 4x4 transformation matrix
)
PostureTask
Maintain desired joint configuration.
COMTask
Control center of mass position.
JointTask
Control individual joint position.
MultiJointTask
Control multiple joints simultaneously.
multi_joint_task = embodik.MultiJointTask(
joint_ids=[0, 2, 4],
target_q=np.array([0.5, 0.3, 0.7]) # Desired angles for selected joints
)
Units Conventions
Use these units consistently across task targets, limits, and tolerances:
- Translation (
x, y, z):m - Rotation (
rx, ry, rz, roll/pitch/yaw, angle errors):rad - Linear velocity:
m/s - Angular velocity:
rad/s - Linear acceleration:
m/s^2 - Angular acceleration:
rad/s^2
For 6D torso pose vectors in PositionIKOptions.torso_constraint, the ordering is
[x, y, z, rx, ry, rz] with units [m, m, m, rad, rad, rad]. Pose bounds are
measured relative to torso_constraint.pose_bounds_reference_pose when set, else
relative to the torso frame at the solve_position seed configuration for that call.
Task Hierarchy
Tasks are solved in priority order (0 = highest).
Typical use:
- Priority
0: end-effector tracking (FrameTask) - Priority
1: secondary balance/posture frame objective (for example torso upright) - Priority
2: nullspace posture bias (PostureTask)
Task Solve Modes
Each task can be solved in one of two modes:
TaskSolveMode.SCALE(default): classic SNS/eSNS behavior that preserves task direction with a scale factor in[0, 1].TaskSolveMode.MIN_ERROR: clamped minimum-error behavior that computes the best feasible residual motion under active constraints.
Automatic fallback from SCALE to MIN_ERROR when scale collapses is
disabled by default for SCALE tasks. Enable it explicitly when needed:
task = solver.add_frame_task("ee", "panda_hand", embodik.TaskType.FRAME_POSE)
task.solve_mode = embodik.TaskSolveMode.SCALE
task.allow_min_error_fallback = True
After solve_velocity(), inspect effective diagnostics:
result = solver.solve_velocity(q)
print(result.task_modes_effective)
print(result.task_used_fallback)
Notes:
- User-created tasks default to
SCALE. - User-created tasks default to
allow_min_error_fallback = False. - Internal nullspace-bias posture tasks used by
solve_position()run inMIN_ERRORmode and are placed after the optional internal torso objective.
PostureTask Joint Selection and Weights
PostureTask supports explicit selection and per-joint weighting:
posture = solver.add_posture_task("posture")
posture.set_controlled_joint_indices([0, 1, 2])
posture.set_controlled_joint_weights(np.array([2.0, 1.0, 0.5]))
This behavior is consistent with a diagonal selection/weighting matrix:
- selected joints contribute to the nullspace objective
- unselected joints are not driven by the posture objective
API Reference
FrameTask
Bases: embodik._embodik_impl.Task
Attributes
__module__
class-attribute
str(object='') -> str str(bytes_or_buffer[, encoding[, errors]]) -> str
Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.str() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to 'strict'.
Functions
__init__
method descriptor
init(self, name: str, model: embodik._embodik_impl.RobotModel, frame_name: str, task_type: embodik._embodik_impl.TaskType = TaskType.FRAME_POSE, priority: int = 0, weight: float = 1.0) -> None
Create a frame tracking task
__new__
builtin
Create and return a new object. See help(type) for accurate signature.
set_orientation_mask
method descriptor
set_orientation_mask(self, mask: numpy.ndarray[dtype=float64, shape=(3), order='C']) -> None
Set orientation mask (which axes to control)
set_position_mask
method descriptor
set_position_mask(self, mask: numpy.ndarray[dtype=float64, shape=(3), order='C']) -> None
Set position mask (which axes to control)
set_target_angular_velocity
method descriptor
set_target_angular_velocity(self, omega: numpy.ndarray[dtype=float64, shape=(3), order='C']) -> None
Set target angular velocity (3D)
set_target_orientation
method descriptor
set_target_orientation(self, rotation: numpy.ndarray[dtype=float64, shape=(3, 3), order='F']) -> None
Set desired orientation as rotation matrix
set_target_pose
method descriptor
set_target_pose(self, position: numpy.ndarray[dtype=float64, shape=(3), order='C'], rotation: numpy.ndarray[dtype=float64, shape=(3, 3), order='F']) -> None
Set desired pose (position + orientation)
set_target_position
method descriptor
set_target_position(self, position: numpy.ndarray[dtype=float64, shape=(3), order='C']) -> None
Set desired position
set_target_position_velocity
method descriptor
set_target_position_velocity(self, velocity: numpy.ndarray[dtype=float64, shape=(3), order='C']) -> None
Set target linear velocity (3D)
PostureTask
Bases: embodik._embodik_impl.Task
Attributes
__module__
class-attribute
str(object='') -> str str(bytes_or_buffer[, encoding[, errors]]) -> str
Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.str() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to 'strict'.
Functions
__init__
method descriptor
init(self, name: str, model: embodik._embodik_impl.RobotModel, priority: int = 10, weight: float = 0.1) -> None init(self, name: str, model: embodik._embodik_impl.RobotModel, controlled_joint_indices: collections.abc.Sequence[int], priority: int = 10, weight: float = 0.1) -> None
Overloaded function.
__init__(self, name: str, model: embodik._embodik_impl.RobotModel, priority: int = 10, weight: float = 0.1) -> None
Create a posture regularization task for all joints
__init__(self, name: str, model: embodik._embodik_impl.RobotModel, controlled_joint_indices: collections.abc.Sequence[int], priority: int = 10, weight: float = 0.1) -> None
Create a posture regularization task for specific joints
__new__
builtin
Create and return a new object. See help(type) for accurate signature.
set_controlled_joint_indices
method descriptor
set_controlled_joint_indices(self, indices: collections.abc.Sequence[int]) -> None
Set controlled joint indices
set_controlled_joint_targets
method descriptor
set_controlled_joint_targets(self, target_values: numpy.ndarray[dtype=float64, shape=(*), order='C']) -> None
Set target values for controlled joints only
set_controlled_joint_weights
method descriptor
set_controlled_joint_weights(self, weights: numpy.ndarray[dtype=float64, shape=(*), order='C']) -> None
Set weights for controlled joints only
set_joint_mask
method descriptor
set_joint_mask(self, mask: numpy.ndarray[dtype=float64, shape=(*), order='C']) -> None
Set joint mask (which joints to control)
set_joint_weights
method descriptor
set_joint_weights(self, weights: numpy.ndarray[dtype=float64, shape=(*), order='C']) -> None
Set per-joint weights
COMTask
Bases: embodik._embodik_impl.Task
Attributes
__module__
class-attribute
str(object='') -> str str(bytes_or_buffer[, encoding[, errors]]) -> str
Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.str() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to 'strict'.
Functions
__init__
method descriptor
init(self, name: str, model: embodik._embodik_impl.RobotModel, priority: int = 0, weight: float = 1.0) -> None
Create a center of mass tracking task
__new__
builtin
Create and return a new object. See help(type) for accurate signature.
set_position_mask
method descriptor
set_position_mask(self, mask: numpy.ndarray[dtype=float64, shape=(3), order='C']) -> None
Set position mask (which axes to control)
JointTask
Bases: embodik._embodik_impl.Task
Attributes
__module__
class-attribute
str(object='') -> str str(bytes_or_buffer[, encoding[, errors]]) -> str
Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.str() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to 'strict'.
Functions
__init__
method descriptor
init(self, name: str, model: embodik._embodik_impl.RobotModel, joint_name: str, target_value: float = 0.0, priority: int = 0, weight: float = 1.0) -> None init(self, name: str, model: embodik._embodik_impl.RobotModel, joint_index: int, target_value: float = 0.0, priority: int = 0, weight: float = 1.0) -> None
Overloaded function.
__init__(self, name: str, model: embodik._embodik_impl.RobotModel, joint_name: str, target_value: float = 0.0, priority: int = 0, weight: float = 1.0) -> None
Create a single joint tracking task by name
__init__(self, name: str, model: embodik._embodik_impl.RobotModel, joint_index: int, target_value: float = 0.0, priority: int = 0, weight: float = 1.0) -> None
Create a single joint tracking task by index
__new__
builtin
Create and return a new object. See help(type) for accurate signature.
MultiJointTask
Bases: embodik._embodik_impl.Task
Attributes
__module__
class-attribute
str(object='') -> str str(bytes_or_buffer[, encoding[, errors]]) -> str
Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.str() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to 'strict'.
Functions
__init__
method descriptor
init(self, name: str, model: embodik._embodik_impl.RobotModel, joint_indices: collections.abc.Sequence[int], target_values: numpy.ndarray[dtype=float64, shape=(), order='C'] = array([], dtype=float64), priority: int = 0, weight: float = 1.0) -> None init(self, name: str, model: embodik._embodik_impl.RobotModel, joint_names: collections.abc.Sequence[str], target_values: numpy.ndarray[dtype=float64, shape=(), order='C'] = array([], dtype=float64), priority: int = 0, weight: float = 1.0) -> None
Overloaded function.
__init__(self, name: str, model: embodik._embodik_impl.RobotModel, joint_indices: collections.abc.Sequence[int], target_values: numpy.ndarray[dtype=float64, shape=(*), order='C'] = array([], dtype=float64), priority: int = 0, weight: float = 1.0) -> None
Create a multi-joint tracking task by indices
__init__(self, name: str, model: embodik._embodik_impl.RobotModel, joint_names: collections.abc.Sequence[str], target_values: numpy.ndarray[dtype=float64, shape=(*), order='C'] = array([], dtype=float64), priority: int = 0, weight: float = 1.0) -> None
Create a multi-joint tracking task by names
__new__
builtin
Create and return a new object. See help(type) for accurate signature.
set_joint_weights
method descriptor
set_joint_weights(self, weights: numpy.ndarray[dtype=float64, shape=(*), order='C']) -> None
Set per-joint weights
set_target_value
method descriptor
set_target_value(self, idx: int, value: float) -> None
Set target value for a specific controlled joint