placo::model#
- class placo.Collision#
Represents a collision between two bodies.
- 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#
Represents a distance between two bodies.
- 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 = '')#
This class contains the robot model, state, and all convenient methods. All the rigid body algorithms (namely, based on pinocchio) are wrapped in this object.
Creates a robot wrapper from a URDF file.
- Parameters:
model_directory – robot model (URDF). It can be a path to an URDF file, or a directory containing an URDF file named ‘robot.urdf’
flags – see Flags
urdf_content – if it is not empty, it will be used as the URDF content instead of loading it from the file
- collision_model: any#
Pinocchio collision model.
- com_jacobian() any #
Jacobian of the CoM position expressed in the world.
- Returns:
jacobian (3 x n matrix)
- com_jacobian_time_variation() any #
Jacobian time variation of the CoM expressed in the world.
- Returns:
jacobian (3 x n matrix)
- com_world() ndarray #
Gets the CoM position in the world.
- distances() list[Distance] #
Computes all minimum distances between current collision pairs.
- Returns:
vector of Distance
- frame_jacobian(frame: str, reference: str = 'local_world_aligned') ndarray #
Frame jacobian, default reference is LOCAL_WORLD_ALIGNED.
- Parameters:
frame – the frame for which we want the jacobian
- Returns:
jacobian (6 x nv matrix), where nv is the size of qd
- frame_jacobian_time_variation(frame: str, reference: str = 'local_world_aligned') ndarray #
Jacobian time variation $dot J$, default reference is LOCAL_WORLD_ALIGNED.
- Parameters:
frame – the frame for which we want the jacobian time variation
reference – the reference frame
- Returns:
jacobian time variation (6 x nv matrix), where nv is the size of qd
- frame_names() list[str] #
All the frame names.
- generalized_gravity() ndarray #
Computes generalized gravity.
- get_T_a_b(frame_a: str, frame_b: str) ndarray #
Gets the transformation matrix from frame b to a.
- Parameters:
frame_a – frame a
frame_b – frame b
- Returns:
transformation
- get_T_world_fbase() ndarray #
Returns the transformation matrix from the fbase frame (which is the root of the URDF) to the world.
- Returns:
transformation
- get_T_world_frame(frame: str) ndarray #
Gets the frame to world transformation matrix for a given frame.
- Parameters:
frame – frame
- Returns:
transformation
- get_joint(name: str) float #
Retrieves a joint value from state.q.
- Parameters:
name – joint name
- Returns:
the joint current (inner state) value (e.g rad for revolute or meters for prismatic)
- get_joint_acceleration(name: str) float #
Gets the joint acceleration from state.qd.
- Parameters:
name – joint name
- Returns:
joint acceleration
- get_joint_offset(name: str) int #
Gets the offset for a given joint in the state (in State::q)
- Parameters:
name – joint name
- Returns:
offset in state.q
- 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 – joint name
- Returns:
offset in state.qd and state.qdd
- get_joint_velocity(name: str) float #
Gets the joint velocity from state.qd.
- Parameters:
name – joint name
- Returns:
joint velocity
- integrate(dt: float) None #
Integrates the internal state for a given dt
- Parameters:
dt – delta time for integration expressed in seconds
- joint_jacobian(joint: str, reference: str = 'local_world_aligned') ndarray #
- joint_names(include_floating_base: bool = False) list[str] #
All the joint names.
- Parameters:
include_floating_base – 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 – 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)
- Returns:
the state
- non_linear_effects() ndarray #
Computes non-linear effects (Corriolis, centrifual and gravitationnal effects)
- relative_position_jacobian(frame_a: str, frame_b: str) ndarray #
Jacobian of the relative position of the position of b expressed in a.
- Parameters:
frame_a – frame A
frame_b – frame B
- Returns:
relative position jacobian of b expressed in a (3 x n matrix)
- 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 – whether to stop at the first collision found
- Returns:
a vector of Collision
- set_T_world_fbase(T_world_fbase: ndarray) None #
Updates the floating base to match the given transformation matrix.
- Parameters:
T_world_fbase – transformation matrix
- set_T_world_frame(frame: str, T_world_frameTarget: ndarray) None #
Updates the floating base status so that the given frame has the given transformation matrix.
- Parameters:
frame – frame to update
T_world_frameTarget – transformation matrix
- 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 – joint name
value – 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 – joint name
value – joint acceleration
- set_joint_limits(name: str, lower: float, upper: float) None #
Sets the limits for a given joint.
- Parameters:
name – joint name
lower – lower limit
upper – upper limit
- set_joint_velocity(name: str, value: float) None #
Sets the joint velocity in state.qd.
- Parameters:
name – joint name
value – joint velocity
- set_torque_limit(name: str, limit: float) None #
Sets the torque limit for a given joint.
- Parameters:
name – joint name
limit – torque limit
- set_velocity_limit(name: str, limit: float) None #
Sets the velocity limit for a given joint.
- Parameters:
name – joint name
limit – joint limit
- set_velocity_limits(limit: float) None #
Set the velocity limits for all the joints.
- Parameters:
limit – limit
- state: RobotWrapper_State#
Robot’s current state.
- static_gravity_compensation_torques(frame: str) 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.
- Parameters:
frame – frame
- static_gravity_compensation_torques_dict(arg2: str) dict #
- torques_from_acceleration_with_fixed_frame(qdd_a: ndarray, fixed_frame: str) 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 – acceleration of the actuated DOFs
fixed_frame – frame
- torques_from_acceleration_with_fixed_frame_dict(arg2: ndarray, arg3: str) dict #
- 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.