spotmicro.GaitGenerator package

Submodules

spotmicro.GaitGenerator.Bezier module

class spotmicro.GaitGenerator.Bezier.BezierGait(dSref=[0.0, 0.0, 0.5, 0.5], dt=0.01, Tswing=0.2)[source]

Bases: object

BernSteinPoly(t, k, point)[source]

Calculate the point on the Berinstein Polynomial based on phase (0->1), point number (0-11), and the value of the control point itself

Parameters:
  • t – phase
  • k – point number
  • point – point value
Returns:

Value through Bezier Curve

BezierSwing(phase, L, LateralFraction, clearance_height=0.04)[source]

Calculates the step coordinates for the Bezier (swing) period

Parameters:
  • phase – current trajectory phase
  • L – step length
  • LateralFraction – determines how lateral the movement is
  • clearance_height – foot clearance height during swing phase
Returns:

X,Y,Z Foot Coordinates relative to unmodified body

Binomial(k)[source]

Solves the binomial theorem given a Bezier point number relative to the total number of Bezier points.

Parameters:k – Bezier point number
Returns:Binomial solution
CheckTouchDown()[source]

Checks whether a reference leg touchdown has occured, and whether this warrants resetting the touchdown time

GenerateTrajectory(L, LateralFraction, YawRate, vel, T_bf_, T_bf_curr, clearance_height=0.06, penetration_depth=0.01, contacts=[0, 0, 0, 0], dt=None)[source]

Calculates the step coordinates for each foot

Parameters:
  • L – step length
  • LateralFraction – determines how lateral the movement is
  • YawRate – the desired body yaw rate
  • vel – the desired step velocity
  • clearance_height – foot clearance height during swing phase
  • penetration_depth – foot penetration depth during stance phase
  • contacts – array containing 1 for contact and 0 otherwise
  • dt – the time step
Returns:

Foot Coordinates relative to unmodified body

GetFootStep(L, LateralFraction, YawRate, clearance_height, penetration_depth, Tstance, T_bf, index, key)[source]

Calculates the step coordinates in either the Bezier or Sine portion of the trajectory depending on the retrieved phase

Parameters:
  • phase – current trajectory phase
  • L – step length
  • LateralFraction – determines how lateral the movement is
  • YawRate – the desired body yaw rate
  • clearance_height – foot clearance height during swing phase
  • penetration_depth – foot penetration depth during stance phase
  • Tstance – the current user-specified stance period
  • T_bf – default body-to-foot Vector
  • index – the foot index in the container
  • key – indicates which foot is being processed
Returns:

Foot Coordinates relative to unmodified body

GetPhase(index, Tstance, Tswing)[source]

Retrieves the phase of an individual leg.

NOTE modification from original paper:

if ti < -Tswing:
ti += Tstride

This is to avoid a phase discontinuity if the user selects a Step Length and Velocity combination that causes Tstance > Tswing.

Parameters:
  • index – the leg’s index, used to identify the required phase lag
  • Tstance – the current user-specified stance period
  • Tswing – the swing period (constant, class member)
Returns:

Leg Phase, and StanceSwing (bool) to indicate whether leg is in stance or swing mode

Get_ti(index, Tstride)[source]

Retrieves the time index for the individual leg

Parameters:
  • index – the leg’s index, used to identify the required phase lag
  • Tstride – the total leg movement period (Tstance + Tswing)
Returns:

the leg’s time index

Increment(dt, Tstride)[source]

Increments the Bezier gait generator’s internal clock (self.time)

Parameters:
  • dt – the time step phase lag
  • Tstride – the total leg movement period (Tstance + Tswing)
Returns:

the leg’s time index

SineStance(phase, L, LateralFraction, penetration_depth=0.0)[source]

Calculates the step coordinates for the Sinusoidal stance period

Parameters:
  • phase – current trajectory phase
  • L – step length
  • LateralFraction – determines how lateral the movement is
  • penetration_depth – foot penetration depth during stance phase
Returns:

X,Y,Z Foot Coordinates relative to unmodified body

StanceStep(phase, L, LateralFraction, YawRate, penetration_depth, T_bf, key, index)[source]

Calculates the step coordinates for the Sine (stance) period using a combination of forward and rotational step coordinates initially decomposed from user input of L, LateralFraction and YawRate

Parameters:
  • phase – current trajectory phase
  • L – step length
  • LateralFraction – determines how lateral the movement is
  • YawRate – the desired body yaw rate
  • penetration_depth – foot penetration depth during stance phase
  • T_bf – default body-to-foot Vector
  • key – indicates which foot is being processed
  • index – the foot index in the container
Returns:

Foot Coordinates relative to unmodified body

SwingStep(phase, L, LateralFraction, YawRate, clearance_height, T_bf, key, index)[source]

Calculates the step coordinates for the Bezier (swing) period using a combination of forward and rotational step coordinates initially decomposed from user input of L, LateralFraction and YawRate

Parameters:
  • phase – current trajectory phase
  • L – step length
  • LateralFraction – determines how lateral the movement is
  • YawRate – the desired body yaw rate
  • clearance_height – foot clearance height during swing phase
  • T_bf – default body-to-foot Vector
  • key – indicates which foot is being processed
  • index – the foot index in the container
Returns:

Foot Coordinates relative to unmodified body

YawCircle(T_bf, index)[source]
Calculates the required rotation of the trajectory plane
for yaw motion
Parameters:
  • T_bf – default body-to-foot Vector
  • index – the foot index in the container
Returns:

phi_arc, the plane rotation angle required for yaw motion

reset()[source]

Resets the parameters of the Bezier Gait Generator

spotmicro.GaitGenerator.Raibert module

Module contents