bicycle Module

ab_matrix(M, C1, K0, K2, v, g)

Calculate the A and B matrices for the Whipple bicycle model linearized about the upright configuration.

Parameters:
Mndarray, shape(2,2)

The mass matrix.

C1ndarray, shape(2,2)

The damping like matrix that is proportional to the speed, v.

K0ndarray, shape(2,2)

The stiffness matrix proportional to gravity, g.

K2ndarray, shape(2,2)

The stiffness matrix proportional to the speed squared, v**2.

vfloat

Forward speed.

gfloat

Acceleration due to gravity.

Returns:
Andarray, shape(4,4)

State matrix.

Bndarray, shape(4,2)

Input matrix.

The states are [roll angle,

steer angle, roll rate, steer rate]

The inputs are [roll torque,

steer torque]

Examples

>>> from bicycleparameters.parameter_dicts import meijaard2007_browser_jason
>>> from bicycleparameters.bicycle import benchmark_par_to_canonical, ab_matrix
>>> M, C1, K0, K2 = benchmark_par_to_canonical(meijaard2007_browser_jason)
>>> A, B = ab_matrix(M, C1, K0, K2, 5.0, 9.81)
>>> A
array([[  0.        ,   0.        ,   1.        ,   0.        ],
       [  0.        ,   0.        ,   0.        ,   1.        ],
       [  8.26150335, -17.52187211,  -0.1488979 ,  -1.07153674],
       [ 17.66475151, -22.88692074,   9.96449204, -14.22097935]])
>>> B
array([[ 0.        ,  0.        ],
       [ 0.        ,  0.        ],
       [ 0.01071772, -0.06613267],
       [-0.06613267,  4.42570676]])
benchmark_par_to_canonical(p)

Returns the canonical matrices of the Whipple bicycle model linearized about the upright constant velocity configuration. It uses the parameter definitions from Meijaard et al. 2007.

Parameters:
pdictionary

A dictionary of the benchmark bicycle parameters. Make sure your units are correct, best to ue the benchmark paper’s units!

Returns:
Mndarray, shape(2,2)

The mass matrix.

C1ndarray, shape(2,2)

The damping like matrix that is proportional to the speed, v.

K0ndarray, shape(2,2)

The stiffness matrix proportional to gravity, g.

K2ndarray, shape(2,2)

The stiffness matrix proportional to the speed squared, v**2.

Notes

This function handles parameters with uncertanties.

lambda_from_abc(rF, rR, a, b, c)

Returns the steer axis tilt, lamba, for the parameter set based on the offsets from the steer axis.

Parameters:
rFfloat or ufloat

Front wheel radius.

rRfloat or ufloat

Rear wheel radius.

afloat or ufloat

The rear wheel offset. The minimum distance from the steer axis to the center of the rear wheel.

bfloat or ufloat

The front wheel offset. The minimum distance from the steer axis to the center of the front wheel.

cfloat or ufloat

The steer axis distance. The distance along the steer axis between the intersection of the front and rear wheel offset lines.

sort_eigenmodes(evals, evecs)

Sort eigenvalues and eigenvectors.

Parameters:
evalsndarray, shape (n, m)

A sequence of n sets of eigenvalues.

evecsndarray, shape (n, m, m)

A sequence of n sets of eigenvectors.

Returns:
evalsorgndarray, shape (n, m)

A sequence of n sets of eigenvalues.

evecsorgndarray, shape (n, m, m)

A sequence of n sets of eigenvectors.

sort_modes(evals, evecs)

Sort eigenvalues and eigenvectors into weave, capsize, caster modes.

Parameters:
evalsndarray, shape (n, 4)

eigenvalues

evecsndarray, shape (n, 4, 4)

eigenvectors

Returns:
weave[‘evals’]ndarray, shape (n, 2)

The eigen value pair associated with the weave mode.

weave[‘evecs’]ndarray, shape (n, 4, 2)

The associated eigenvectors of the weave mode.

capsize[‘evals’]ndarray, shape (n,)

The real eigenvalue associated with the capsize mode.

capsize[‘evecs’]ndarray, shape(n, 4, 1)

The associated eigenvectors of the capsize mode.

caster[‘evals’]ndarray, shape (n,)

The real eigenvalue associated with the caster mode.

caster[‘evecs’]ndarray, shape(n, 4, 1)

The associated eigenvectors of the caster mode.

Notes

This only works on the standard bicycle eigenvalues, not necessarily on any general eigenvalues for the bike model (e.g. there isn’t always a distinct weave, capsize and caster). Some type of check using the derivative of the curves could make it more robust.

trail(rF, lam, fo)

Calculate the trail and mechanical trail.

Parameters:
rFfloat

The front wheel radius

lamfloat

The steer axis tilt (pi/2 - headtube angle). The angle between the headtube and a vertical line.

fofloat

The fork offset

Returns:
c: float

Trail

cm: float

Mechanical Trail