placo::model#

class placo.Collision#
bodyA: str#

Name of the body A.

bodyB: str#

Name of the body B.

get_contact(arg2: int) ndarray#
objA: int#

Index of object A in the collision geometry.

objB: int#

Index of object B in the collision geometry.

parentA: any#

The joint parent of body A.

parentB: any#

The joint parent of body B.

class placo.Distance#
min_distance: float#

Current minimum distance between the two objects.

objA: int#

Index of object A in the collision geometry.

objB: int#

Index of object B in the collision geometry.

parentA: any#

Parent joint of body A.

parentB: any#

Parent joint of body B.

pointA: ndarray#

Point of object A considered.

pointB: ndarray#

Point of object B considered.

class placo.RobotWrapper(model_directory: str, flags: int = 0, urdf_content: str = '')#

Creates a robot wrapper from a URDF file.

Parameters:
  • model_directory (str) – robot model (URDF). It can be a path to an URDF file, or a directory containing an URDF file named ‘robot.urdf’

  • flags (int) – see Flags

  • urdf_content (str) – if it is not empty, it will be used as the URDF content instead of loading it from the file

add_q_noise(noise: float) None#

Adds some noise to the configuration.

centroidal_map() ndarray#

Centroidal map.

collision_model: any#

Pinocchio collision model.

com_jacobian() ndarray#

Jacobian of the CoM position expressed in the world.

com_jacobian_time_variation() ndarray#

Jacobian time variation of the CoM expressed in the world.

com_world() ndarray#

Gets the CoM position in the world.

compute_hessians() None#

Compute kinematics hessians.

distances() list[Distance]#

Computes all minimum distances between current collision pairs.

Returns:

<Element ‘para’ at 0xffd173f7c630>

frame_jacobian(frame: any, ref: any = None) ndarray#

Frame jacobian, default reference is LOCAL_WORLD_ALIGNED.

Parameters:

frame (any) – the frame for which we want the jacobian

Returns:

<Element ‘para’ at 0xffd173f688b0>

frame_jacobian_time_variation(frame: any, ref: any = None) ndarray#

Jacobian time variation $dot J$, default reference is LOCAL_WORLD_ALIGNED.

Parameters:

frame (any) – the frame for which we want the jacobian time variation

Returns:

<Element ‘para’ at 0xffd173f6aa70>

frame_names() list[str]#

All the frame names.

generalized_gravity() ndarray#

Computes generalized gravity.

get_T_a_b(index_a: any, index_b: any) ndarray#

Gets the transformation matrix from frame b to a.

Parameters:
  • index_a (any) – frame a

  • index_b (any) – frame b

get_T_world_fbase() ndarray#

Returns the transformation matrix from the fbase frame (which is the root of the URDF) to the world.

get_T_world_frame(index: any) ndarray#

Gets the frame to world transformation matrix for a given frame.

Parameters:

index (any) – frame index

get_frame_hessian(frame: any, joint_v_index: int) ndarray#

Get the component for the hessian of a given frame for a given joint.

get_joint(name: str) float#

Retrieves a joint value from state.q.

Parameters:

name (str) – joint name

get_joint_acceleration(name: str) float#

Gets the joint acceleration from state.qd.

Parameters:

name (str) – joint name

get_joint_limits(name: str) any#

Gets the limits for a given joint.

Parameters:

name (str) – joint name

get_joint_offset(name: str) int#

Gets the offset for a given joint in the state (in State::q)

Parameters:

name (str) – joint name

get_joint_v_offset(name: str) int#

Gets the offset for a given joint in the state (in State::qd and State::qdd)

Parameters:

name (str) – joint name

get_joint_velocity(name: str) float#

Gets the joint velocity from state.qd.

Parameters:

name (str) – joint name

integrate(dt: float) None#

Integrates the internal state for a given dt

Parameters:

dt (float) – delta time for integration expressed in seconds

joint_jacobian(joint: str, reference: str = 'local_world_aligned') ndarray#

Joint jacobian, default reference is LOCAL_WORLD_ALIGNED.

joint_names(include_floating_base: bool = False) list[str]#

All the joint names.

Parameters:

include_floating_base (bool) – whether to include the floating base joint (false by default)

load_collision_pairs(filename: str) None#

Loads collision pairs from a given JSON file.

Parameters:

filename (str) – path to collisions.json file

make_solver() KinematicsSolver#
mass_matrix() ndarray#

Computes the mass matrix.

model: any#

Pinocchio model.

neutral_state() RobotWrapper_State#

builds a neutral state (neutral position, zero speed)

non_linear_effects() ndarray#

Computes non-linear effects (Corriolis, centrifual and gravitationnal effects)

relative_position_jacobian(frame_a: any, frame_b: any) ndarray#

Jacobian of the relative position of the position of b expressed in a.

Parameters:
  • frame_a (any) – frame index A

  • frame_b (any) – frame index B

reset() None#

Reset internal states, this sets q to the neutral position, qd and qdd to zero.

self_collisions(stop_at_first: bool = False) list[Collision]#

Finds the self collision in current state, if stop_at_first is true, it will stop at the first collision found.

Parameters:

stop_at_first (bool) – whether to stop at the first collision found

Returns:

<Element ‘para’ at 0xffd173f7ca90>

set_T_world_fbase(T_world_fbase: ndarray) None#

Updates the floating base to match the given transformation matrix.

Parameters:

T_world_fbase (numpy.ndarray) – transformation matrix

set_T_world_frame(frame: any, T_world_frameTarget: ndarray) None#

Updates the floating base status so that the given frame has the given transformation matrix.

Parameters:
  • frame (any) – frame to update

  • T_world_frameTarget (numpy.ndarray) – transformation matrix

set_gear_ratio(joint_name: str, rotor_gear_ratio: float) None#

Updates the rotor gear ratio (used for apparent inertia computation in the dynamics)

set_gravity(gravity: ndarray) None#

Sets the gravity vector.

set_joint(name: str, value: float) None#

Sets the value of a joint in state.q.

Parameters:
  • name (str) – joint name

  • value (float) – joint value (e.g rad for revolute or meters for prismatic)

set_joint_acceleration(name: str, value: float) None#

Sets the joint acceleration in state.qd.

Parameters:
  • name (str) – joint name

  • value (float) – joint acceleration

set_joint_limits(name: str, lower: float, upper: float) None#

Sets the limits for a given joint.

Parameters:
  • name (str) – joint name

  • lower (float) – lower limit

  • upper (float) – upper limit

set_joint_velocity(name: str, value: float) None#

Sets the joint velocity in state.qd.

Parameters:
  • name (str) – joint name

  • value (float) – joint velocity

set_rotor_inertia(joint_name: str, rotor_inertia: float) None#

Updates the rotor inertia (used for apparent inertia computation in the dynamics)

set_torque_limit(name: str, limit: float) None#

Sets the torque limit for a given joint.

Parameters:
  • name (str) – joint name

  • limit (float) – torque limit

set_velocity_limit(name: str, limit: float) None#

Sets the velocity limit for a given joint.

Parameters:
  • name (str) – joint name

  • limit (float) – joint limit

set_velocity_limits(limit: float) None#

Set the velocity limits for all the joints.

Parameters:

limit (float) – limit

state: RobotWrapper_State#

Robot’s current state.

static_gravity_compensation_torques(frameIndex: any) ndarray#

Computes torques needed by the robot to compensate for the generalized gravity, assuming that the given frame is the (only) contact supporting the robot.

static_gravity_compensation_torques_dict(arg2: str) dict#
torques_from_acceleration_with_fixed_frame(qdd_a: ndarray, frameIndex: any) ndarray#

Computes required torques in the robot DOFs for a given acceleration of the actuated DOFs, assuming that the given frame is fixed.

Parameters:

qdd_a (numpy.ndarray) – acceleration of the actuated DOFs

torques_from_acceleration_with_fixed_frame_dict(qdd_a: ndarray, frame: str) dict#

Computes the torque required to reach given acceleration in fixed frame

total_mass() float#

Total mass.

update_kinematics() None#

Update internal computation for kinematics (frames, jacobian). This method should be called when the robot state has changed.

visual_model: any#

Pinocchio visual model.

class placo.RobotWrapper_State#
q: ndarray#

joints configuration $q$

qd: ndarray#

joints velocity $dot q$

qdd: ndarray#

joints acceleration $ddot q$