placo::kinematics#

class placo.AvoidSelfCollisionsKinematicsConstraint#
configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

name: str#

Object name.

priority: any#

Object priority.

self_collisions_margin: float#

Margin for self collisions [m].

self_collisions_trigger: float#

Distance that triggers the constraint [m].

class placo.AxisAlignTask(frame_index: any, axis_frame: ndarray, targetAxis_world: ndarray)#
A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

axis_frame: ndarray#

Axis in the frame.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

frame_index: any#

Target frame.

name: str#

Object name.

priority: any#

Object priority.

targetAxis_world: ndarray#

Target axis in the world.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.CentroidalMomentumTask(L_world: ndarray)#

See KinematicsSolver::add_centroidal_momentum_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

L_world: ndarray#

Target centroidal angular momentum in the world.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

mask: AxisesMask#

Axises mask.

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.CoMPolygonConstraint(polygon: list[ndarray], margin: float = 0.0)#

Ensures that the CoM (2D) lies inside the given polygon.

Parameters:

polygon – Clockwise polygon

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

dcm: bool#

If set to true, the DCM will be used instead of the CoM.

margin: float#

Margin for the polygon constraint (minimum distance between the CoM and the polygon)

name: str#

Object name.

omega: float#

If DCM mode is enabled, the constraint will be applied on the DCM instead of the CoM with the following omega (sqrt(g / h))

polygon: list[ndarray]#

Clockwise polygon.

priority: any#

Object priority.

class placo.CoMTask(target_world: ndarray)#

See KinematicsSolver::add_com_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

mask: AxisesMask#

Mask.

name: str#

Object name.

priority: any#

Object priority.

target_world: ndarray#

Target for the CoM in the world.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.ConeConstraint(frame_a: any, frame_b: any, angle_max: float)#

A cone constraint is a constraint where the z-axis of frame a and frame b should remaine within a cone of angle angle_max.

With a cone constraint, the z-axis of frame a and frame b should remaine within a cone of angle angle_max.

Parameters:
  • frame_a

  • frame_b

  • angle_max

N: int#

Number of slices used to discretize the cone.

angle_max: float#

Maximum angle allowable by the cone constraint (between z-axis of frame_a and frame_b)

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

name: str#

Object name.

priority: any#

Object priority.

range: float#

Range of the cone discretization (in radians). The cone is discretized in [-range, range] around the current orientation.

class placo.DistanceTask(frame_a: any, frame_b: any, distance: float)#

see KinematicsSolver::add_distance_task

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

distance: float#

Target distance between A and B.

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

frame_a: any#

Frame A.

frame_b: any#

Frame B.

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.FrameTask(position: PositionTask, orientation: OrientationTask)#

see KinematicsSolver::add_frame_task

T_world_frame: any#
configure(name: str, priority: str = 'soft', position_weight: float = 1.0, orientation_weight: float = 1.0) None#

Configures the frame task.

Parameters:
  • name – task name

  • priority – task priority

  • position_weight – weight for the position task

  • orientation_weight – weight for the orientation task

orientation() OrientationTask#

Orientation task.

position() PositionTask#

Position task.

class placo.GearTask#

see KinematicsSolver::add_gear_task

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

add_gear(target: str, source: str, ratio: float) None#

Adds a gear constraint, you can add multiple source for the same target, they will be summed.

Parameters:
  • target – target joint

  • source – source joint

  • ratio – ratio

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

name: str#

Object name.

priority: any#

Object priority.

set_gear(target: str, source: str, ratio: float) None#

Sets a gear constraint.

Parameters:
  • target – target joint

  • source – source joint

  • ratio – ratio

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.JointsTask#

see KinematicsSolver::add_joints_task

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

name: str#

Object name.

priority: any#

Object priority.

set_joint(joint: str, target: float) None#

Sets a joint target.

Parameters:
  • joint – joint

  • target – target value

set_joints(arg2: dict) None#
update() None#

Update the task A and b matrices from the robot state and targets.

class placo.KinematicsConstraint#
configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

name: str#

Object name.

priority: any#

Object priority.

class placo.KinematicsSolver(robot_: RobotWrapper)#

Inverse Kinematics solver.

N: int#

Size of the problem (number of variables)

add_avoid_self_collisions_constraint() AvoidSelfCollisionsKinematicsConstraint#

Adds a self collision avoidance constraint.

Returns:

constraint

add_axisalign_task(frame: str, axis_frame: ndarray, targetAxis_world: ndarray) AxisAlignTask#

Adds an axis alignment task. The goal here is to keep the given axis (expressed in the given frame) aligned with another one (given in the world)

Parameters:
  • frame – the robot frame we want to control

  • axis_frame – the axis to align, expressed in the robot frame

  • targetAxis_world – the target axis (in the world) we want to be aligned with

add_centroidal_momentum_task(L_world: ndarray) CentroidalMomentumTask#

Adding a centroidal momentum task.

Parameters:

L_world – desired centroidal angular momentum in the world

Returns:

centroidal task

add_com_polygon_constraint(polygon: list[ndarray], margin: float = 0.0) CoMPolygonConstraint#

Adds a CoM polygon constraint.

Parameters:
  • polygon – clockwise polygon

  • margin – margin

Returns:

constraint

add_com_task(targetCom_world: ndarray) CoMTask#

Adds a com position task.

Parameters:

targetCom_world – the target position, expressed in the world (as T_world_frame)

Returns:

com task

add_cone_constraint(frame_a: str, frame_b: str, alpha_max: float) ConeConstraint#

Adds a Cone constraint.

Parameters:
  • frame_a – frame A

  • frame_b – frame B

  • alpha_max – alpha max (in radians) between the frame z-axis and the cone frame zt-axis

  • T_world_cone – cone frame

Returns:

constraint

add_constraint(constraint: any) any#
add_distance_task(frame_a: str, frame_b: str, distance: float) DistanceTask#

Adds a distance task to be maintained between two frames.

Parameters:
  • frame_a – frame a

  • frame_b – frame b

  • distance – distance to maintain

Returns:

distance task

add_frame_task(frame: str, T_world_frame: ndarray) FrameTask#

Adds a frame task, this is equivalent to a position + orientation task, resulting in decoupled tasks for a given frame.

Parameters:
  • frame – the robot frame we want to control

  • T_world_frame – the target for the frame we want to control, expressed in the world (as T_world_frame)

  • priority – task priority (hard: equality constraint, soft: objective function)

Returns:

frame task

add_gear_task() GearTask#

Adds a gear task, allowing replication of joints.

Returns:

gear task

add_joints_task() JointsTask#

Adds joints task.

Returns:

joints task

add_kinetic_energy_regularization_task(magnitude: float = 1e-06) KineticEnergyRegularizationTask#

Adds a kinetic energy regularization task for a given magnitude.

Parameters:

magnitude – regularization magnitude

Returns:

regularization task

add_orientation_task(frame: str, R_world_frame: ndarray) OrientationTask#

Adds an orientation task.

Parameters:
  • frame – the robot frame we want to control

  • R_world_frame – the target orientation we want to achieve, expressed in the world (as T_world_frame)

Returns:

orientation task

add_position_task(frame: str, target_world: ndarray) PositionTask#

Adds a position task.

Parameters:
  • frame – the robot frame we want to control

  • target_world – the target position, expressed in the world (as T_world_frame)

Returns:

position task

add_q_noise(noise: float = 1e-05) None#

Adds some noise on the configuration of the robot (q)

Parameters:

noise – noise level, expressed in ratio of the joint limits

add_regularization_task(magnitude: float = 1e-06) RegularizationTask#

Adds a regularization task for a given magnitude.

Parameters:

magnitude – regularization magnitude

Returns:

regularization task

add_relative_frame_task(frame_a: str, frame_b: str, T_a_b: ndarray) RelativeFrameTask#

Adds a relative frame task.

Parameters:
  • frame_a – frame a

  • frame_b – frame b

  • T_a_b – desired transformation

Returns:

relative frame task

add_relative_orientation_task(frame_a: str, frame_b: str, R_a_b: ndarray) RelativeOrientationTask#

Adds a relative orientation task.

Parameters:
  • frame_a – frame a

  • frame_b – frame b

  • R_a_b – the desired orientation

Returns:

relative orientation task

add_relative_position_task(frame_a: str, frame_b: str, target: ndarray) RelativePositionTask#

Adds a relative position task.

Parameters:
  • frame_a – frame a

  • frame_b – frame b

  • target – the target vector between frame a and b (expressed in world)

Returns:

relative position task

add_task(task: any) any#
add_wheel_task(joint: str, radius: float, omniwheel: bool = False) WheelTask#

Adds a wheel task.

Parameters:
  • joint – joint name

  • radius – wheel radius

  • omniwheel – true if it’s an omniwheel (can slide laterally)

Returns:

the wheel task

clear() None#

Clears the internal tasks.

dt: float#

solver dt (for speeds limiting)

dump_status() None#

Shows the tasks status.

enable_joint_limits(enable: bool) None#

Enables/disables joint limits inequalities.

enable_velocity_limits(enable: bool) None#

Enables/disables joint velocity inequalities.

mask_dof(dof: str) None#

Masks (disables a DoF) from being used by the QP solver (it can’t provide speed)

Parameters:

dof – the dof name

mask_fbase(masked: bool) None#

Decides if the floating base should be masked.

problem: Problem#

The underlying QP problem.

remove_constraint(constraint: KinematicsConstraint) None#

Removes aconstraint from the solver.

Parameters:

constraint – constraint

remove_task(task: FrameTask) None#

Removes a frame task from the solver.

Parameters:

task – task

robot: RobotWrapper#

The robot controlled by this solver.

scale: float#

scale obtained when using tasks scaling

solve(apply: bool = False) ndarray#

Constructs the QP problem and solves it.

Parameters:

apply – apply the solution to the robot model

Returns:

the vector containing delta q, which are target variations for the robot degrees of freedom.

tasks_count() int#

Number of tasks.

unmask_dof(dof: str) None#

Unmsks (enables a DoF) from being used by the QP solver (it can provide speed)

Parameters:

dof – the dof name

class placo.KineticEnergyRegularizationTask#
A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.OrientationTask(frame_index: any, R_world_frame: ndarray)#

See KinematicsSolver::add_orientation_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

R_world_frame: ndarray#

Target frame orientation in the world.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

frame_index: any#

Frame.

mask: AxisesMask#

Mask.

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.PositionTask(frame_index: any, target_world: ndarray)#

See KinematicsSolver::add_position_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

frame_index: any#

Frame.

mask: AxisesMask#

Mask.

name: str#

Object name.

priority: any#

Object priority.

target_world: ndarray#

Target position in the world.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.RegularizationTask#
A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.RelativeFrameTask(position: RelativePositionTask, orientation: RelativeOrientationTask)#

see KinematicsSolver::add_relative_frame_task

T_a_b: any#
configure(name: str, priority: str = 'soft', position_weight: float = 1.0, orientation_weight: float = 1.0) None#

Configures the relative frame task.

Parameters:
  • name – task name

  • priority – task priority

  • position_weight – weight for the position task

  • orientation_weight – weight for the orientation task

orientation() RelativeOrientationTask#

Relative orientation.

position() RelativePositionTask#

Relative position.

class placo.RelativeOrientationTask(frame_a: any, frame_b: any, R_a_b: ndarray)#

See KinematicsSolver::add_relative_orientation_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

R_a_b: ndarray#

Target relative orientation of b in a.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

frame_a: any#

Frame A.

frame_b: any#

Frame B.

mask: AxisesMask#

Mask.

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.RelativePositionTask(frame_a: any, frame_b: any, target: ndarray)#

See KinematicsSolver::add_relative_position_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

frame_a: any#

Frame A.

frame_b: any#

Frame B.

mask: AxisesMask#

Mask.

name: str#

Object name.

priority: any#

Object priority.

target: ndarray#

Target position of B in A.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.Task#

Represents a task for the kinematics solver.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

name: str#

Object name.

priority: any#

Object priority.

update() None#

Update the task A and b matrices from the robot state and targets.

class placo.WheelTask(joint: str, radius: float, omniwheel: bool = False)#

See KinematicsSolver::add_wheel_task.

A: ndarray#

Matrix A in the task Ax = b, where x are the joint delta positions.

T_world_surface: ndarray#

Target position in the world.

b: ndarray#

Vector b in the task Ax = b, where x are the joint delta positions.

configure(name: str, priority: any, weight: float = 1.0) None#

Configures the object.

Parameters:
  • name – task name

  • priority – task priority (hard, soft or scaled)

  • weight – task weight

error() ndarray#

Task errors (vector)

Returns:

task errors

error_norm() float#

The task error norm.

Returns:

task error norm

joint: str#

Frame.

name: str#

Object name.

omniwheel: bool#

Omniwheel (can slide laterally)

priority: any#

Object priority.

radius: float#

Wheel radius.

update() None#

Update the task A and b matrices from the robot state and targets.