placo::humanoid#
- class placo.Footstep(foot_width: float, foot_length: float)#
A footstep is the position of a specific foot on the ground.
- foot_length: float#
- foot_width: float#
- frame: ndarray#
- kick: bool#
- static polygon_contains(polygon: list[ndarray], point: ndarray) bool #
- side: any#
- support_polygon() list[ndarray] #
- class placo.FootstepsPlanner(parameters: HumanoidParameters)#
Initializes the solver.
- Parameters:
parameters – Parameters of the walk
- static make_supports(footsteps: list[Footstep], start: bool = True, middle: bool = False, end: bool = True) list[Support] #
Generate the supports from the footsteps.
- Parameters:
start – should we add a double support at the begining of the move?
middle – should we add a double support between each step ?
end – should we add a double support at the end of the move?
- Returns:
vector of supports to use. It starts with initial double supports, and add double support phases between footsteps.
- class placo.FootstepsPlannerNaive(parameters: HumanoidParameters)#
-
- configure(T_world_left_target: ndarray, T_world_right_target: ndarray) None #
Configure the naive footsteps planner.
- Parameters:
T_world_left_target – Targetted frame for the left foot
T_world_right_target – Targetted frame for the right foot
- static make_supports(footsteps: list[Footstep], start: bool = True, middle: bool = False, end: bool = True) list[Support] #
Generate the supports from the footsteps.
- Parameters:
start – should we add a double support at the begining of the move?
middle – should we add a double support between each step ?
end – should we add a double support at the end of the move?
- Returns:
vector of supports to use. It starts with initial double supports, and add double support phases between footsteps.
- class placo.FootstepsPlannerRepetitive(parameters: HumanoidParameters)#
-
- configure(x: float, y: float, theta: float, steps: int) None #
Compute the next footsteps based on coordinates expressed in the support frame laterally translated of +/- feet_spacing.
- Parameters:
x – Longitudinal distance
y – Lateral distance
theta – Angle
steps – Number of steps
- static make_supports(footsteps: list[Footstep], start: bool = True, middle: bool = False, end: bool = True) list[Support] #
Generate the supports from the footsteps.
- Parameters:
start – should we add a double support at the begining of the move?
middle – should we add a double support between each step ?
end – should we add a double support at the end of the move?
- Returns:
vector of supports to use. It starts with initial double supports, and add double support phases between footsteps.
- class placo.HumanoidParameters#
A collection of parameters that can be used to define the capabilities and the constants behind planning and control of an humanoid robot.
- double_support_duration() float #
Duratuon [s]of a double support.
- double_support_ratio: float#
Duration ratio between single support and double support.
- double_support_timesteps() int #
Duration [timesteps] of a double support.
- dt() float #
dt for planning [s]
- ellipsoid_clip(step: ndarray) ndarray #
Applies the ellipsoid clipping to a given step size (dx, dy, dtheta)
- feet_spacing: float#
Lateral spacing between feet [m].
- foot_length: float#
Foot length [m].
- foot_width: float#
Foot width [m].
- foot_zmp_target_x: float#
Target offset for the ZMP x reference trajectory in the foot frame [m].
- foot_zmp_target_y: float#
Target offset for the ZMP x reference trajectory in the foot frame, positive is “outward” [m].
- has_double_support() bool #
Checks if the walk resulting from those parameters will have double supports.
- kick_support_duration() float #
Duration [s] of a kick support.
- kick_support_ratio: float#
Duration ratio between single support and kick support.
- kick_support_timesteps() int #
Duration [timesteps]of a kick support.
- planned_timesteps: int#
Planning horizon for the CoM trajectory.
- replan_timesteps: int#
Number of timesteps between each replan. Support phases have to last longer than [replan_frequency * dt] or their duration has to be equal to 0.
- single_support_duration: float#
SSP duration [s].
- single_support_timesteps: int#
Number of timesteps for one single support.
- startend_double_support_duration() float #
Duration [s] of a start/end double support.
- startend_double_support_ratio: float#
Duration ratio between single support and double support.
- startend_double_support_timesteps() int #
Duration [timesteps]of a start/end double support.
- walk_com_height: float#
Target CoM height while walking [m].
- walk_dtheta_spacing: float#
How much we need to space the feet per dtheta [m/rad].
- walk_foot_height: float#
How height the feet are rising while walking [m].
- walk_foot_rise_ratio: float#
ratio of time spent at foot height during the step
- walk_max_dtheta: float#
Maximum step (yaw)
- walk_max_dx_backward: float#
Maximum step (backward)
- walk_max_dx_forward: float#
Maximum step (forward)
- walk_max_dy: float#
Maximum step (lateral)
- walk_trunk_pitch: float#
Trunk pitch while walking [rad].
- zmp_margin: float#
Margin for the ZMP to live in the support polygon [m].
- zmp_reference_weight: float#
Weight for ZMP reference in the solver.
- class placo.HumanoidRobot(model_directory: str = 'robot', flags: int = 0, urdf_content: str = '')#
- T_world_support: ndarray#
Transformation from support to world.
- 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.
- dcm(com_velocity: ndarray, omega: float) ndarray #
Compute the Divergent Component of Motion (DCM)
- Parameters:
com_velocity – CoM velocity
omega – Natural frequency of the LIP (= sqrt(g/h))
- Returns:
DCM
- distances() list[Distance] #
Computes all minimum distances between current collision pairs.
- Returns:
vector of Distance
- ensure_on_floor() None #
Place the robot on its support on the floor.
- 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_T_world_left() ndarray #
- get_T_world_right() ndarray #
- get_T_world_trunk() ndarray #
- get_com_velocity(support: any, omega_b: ndarray) ndarray #
Compute the center of mass velocity from the speed of the motors and the orientation of the trunk.
- Parameters:
support – Support side
omega_b – Trunk angular velocity in the body frame
- Returns:
Center of mass velocity
- 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
- get_support_side() HumanoidRobot_Side #
- get_torques(acc_a: ndarray, contact_forces: ndarray, use_non_linear_effects: bool = False) ndarray #
Compute the torques of the motors from the contact forces.
- Parameters:
acc_a – Accelerations of the actuated DoFs
contact_forces – Contact forces from the feet (forces are supposed normal to the ground)
use_non_linear_effects – If true, non linear effects are taken into account (state.qd necessary)
- Returns:
Torques of the motors
- get_torques_dict(arg2: ndarray, arg3: ndarray, arg4: bool) dict #
- 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)
- static other_side(side: any) any #
- 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 #
- support_is_both: bool#
Are both feet supporting the robot.
- 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.
- update_support_side(side: str) None #
- visual_model: any#
Pinocchio visual model.
- zmp(com_acceleration: ndarray, omega: float) ndarray #
Compute the Zero-tilting Moment Point (ZMP)
- Parameters:
com_acceleration – CoM acceleration
omega – Natural frequency of the LIP (= sqrt(g/h))
- Returns:
ZMP
- class placo.LIPM(problem: Problem, timesteps: int, dt: float, initial_pos: ndarray, initial_vel: ndarray, initial_acc: ndarray)#
LIPM is an helper that can be used to build problem involving LIPM dynamics. The decision variables introduced here are jerks, which is piecewise constant.
- acc(timestep: int) Expression #
- static compute_omega(com_height: float) float #
Compute the natural frequency of a LIPM given its height (omega = sqrt(g / h))
- dcm(timestep: int, omega: float) Expression #
- dzmp(timestep: int, omega_2: float) Expression #
- get_trajectory() LIPMTrajectory #
- jerk(timestep: int) Expression #
- pos(timestep: int) Expression #
- vel(timestep: int) Expression #
- x: Integrator#
- y: Integrator#
- zmp(timestep: int, omega_2: float) Expression #
- class placo.LIPMTrajectory#
- acc(t: float) ndarray #
- dcm(t: float, omega: float) ndarray #
- dzmp(t: float, omega_2: float) ndarray #
- jerk(t: float) ndarray #
- pos(t: float) ndarray #
- vel(t: float) ndarray #
- zmp(t: float, omega_2: float) ndarray #
- class placo.Support#
A support is a set of footsteps (can be one or two foot on the ground)
- end: bool#
- footstep_frame(side: any) ndarray #
Returns the frame for a given side (if present)
- Parameters:
side – the side we want the frame (left or right foot)
- Returns:
a frame
- frame() ndarray #
Returns the frame for the support. It will be the (interpolated) average of footsteps frames.
- Returns:
a frame
- is_both() bool #
Checks whether this support is a double support.
- kick() bool #
- set_end(arg2: bool) None #
- set_start(arg2: bool) None #
- side() any #
The support side (you should call is_both() to be sure it’s not a double support before)
- start: bool#
- support_polygon() list[ndarray] #
- class placo.SwingFoot#
A cubic fitting of swing foot, see: https://scaron.info/doc/pymanoid/walking-pattern-generation.html#pymanoid.swing_foot.SwingFoot.
- static make_trajectory(t_start: float, t_end: float, height: float, start: ndarray, target: ndarray) SwingFootTrajectory #
- static remake_trajectory(old_trajectory: SwingFootTrajectory, t: float, target: ndarray) SwingFootTrajectory #
- class placo.SwingFootCubic#
Cubic swing foot.
- static make_trajectory(t_start: float, t_end: float, height: float, rise_ratio: float, start: ndarray, target: ndarray) SwingFootCubicTrajectory #
- class placo.SwingFootQuintic#
A quintic fitting of the swing foot.
- static make_trajectory(t_start: float, t_end: float, height: float, start: ndarray, target: ndarray) SwingFootQuinticTrajectory #
- class placo.WalkPatternGenerator(robot: HumanoidRobot, parameters: HumanoidParameters)#
- can_replan_supports(trajectory: WalkTrajectory, t_replan: float) bool #
Checks if a trajectory can be replanned for supports.
- plan(supports: list[Support], initial_com_world: ndarray, t_start: float = 0.0) WalkTrajectory #
Plan a walk trajectory following given footsteps based on the parameters of the WPG.
- Parameters:
supports – Supports generated from the foosteps to follow
- Returns:
Planned trajectory
- replan(supports: list[Support], old_trajectory: WalkTrajectory, t_replan: float) WalkTrajectory #
Update the walk trajectory to follow given footsteps based on the parameters of the WPG.
- Parameters:
supports – Supports generated from the current foosteps or the new ones to follow. Contain the current support
old_trajectory – Current walk trajectory
t_replan – The time (in the original trajectory) where the replan happens
- Returns:
True if the trajectory have been replanned, false it hasn’t
- replan_supports(planner: FootstepsPlanner, trajectory: WalkTrajectory, t_replan: float) list[Support] #
Replan the supports for a given trajectory given a footsteps planner.
- class placo.WalkTasks#
- com_x: float#
- com_y: float#
- get_tasks_error() any #
- initialize_tasks(solver: KinematicsSolver, robot: HumanoidRobot) None #
- reach_initial_pose(T_world_left: ndarray, feet_spacing: float, com_height: float, trunk_pitch: float) None #
- remove_tasks() None #
- scaled: bool#
- solver: KinematicsSolver#
- trunk_mode: bool#
- trunk_orientation_task: OrientationTask#
- update_tasks(T_world_left: ndarray, T_world_right: ndarray, com_world: ndarray, R_world_trunk: ndarray) None #
- update_tasks_from_trajectory(arg2: WalkTrajectory, arg3: float) None #
- class placo.WalkTrajectory#
- apply_transform(T: ndarray) None #
Applies a given transformation to the left of all values issued by the trajectory.
- get_R_world_trunk(t: float) ndarray #
- get_T_world_left(t: float) ndarray #
- get_T_world_right(t: float) ndarray #
- get_a_world_CoM(t: float) ndarray #
- get_j_world_CoM(t: float) ndarray #
- get_next_support(t: float, n: int = 1) Support #
Returns the nth next support corresponding to the given time in the trajectory.
- get_p_world_CoM(t: float) ndarray #
- get_p_world_DCM(t: float, omega: float) ndarray #
- get_p_world_ZMP(t: float, omega: float) ndarray #
- get_part_t_start(t: float) float #
Returns the trajectory time start for the support corresponding to the given time.
- get_prev_support(t: float, n: int = 1) Support #
Returns the nth previous support corresponding to the given time in the trajectory.
- get_support(t: float) Support #
Returns the support corresponding to the given time in the trajectory.
- get_v_world_CoM(t: float) ndarray #
- jerk_planner_timesteps: int#
- support_is_both(t: float) bool #
- support_side(t: float) any #
- t_end: float#
- t_start: float#