klampt.math.autodiff.math_ad module

Basic math / linear algebra routines. Defines the following AD functions:

Function

Derivative

Notes

exp

1

log

1

sqrt

1

sin

Y

cos

Y

dot

Y

linear

Y

Produces \(A x\) for a fixed A

quadratric

Y

Produces \(x^T A x\) for a fixed A

bilinear

Y

Produces \(x^T A y\) for a fixed A

ShapedDot

Y

Reshapes a vector before performing dot

norm

1

Standard L2 norm

normSquared

Y

distance

1

Standard L2 norm

distanceSquared

Y

unit

N

cross

1

interpolate

1

Module contents

exp

Autodiff'ed function comparable to np.exp.

log

Autodiff'ed function comparable to np.log.

sqrt

Autodiff'ed function comparable to np.sqrt.

sin

Autodiff'ed function comparable to np.sin.

cos

Autodiff'ed function comparable to np.cos.

dot

Autodiff'ed function comparable to np.dot.

linear(A, x)

Autodiff'ed function comparable to np.dot(A,x).

quadratric(A, x)

Autodiff'ed function comparable to np.dot(x,np.dot(A,x)).

bilinear(x, A, y)

Autodiff'ed function comparable to np.dot(x,np.dot(A,y)).

ShapedDot([shape1, shape2])

This function is used to do matrix-vector products, which are by normally not supported by the dot function since all arguments are flattened 1D arrays.

norm

Autodiff'ed function comparable to np.linalg.norm.

normSquared

Autodiff'ed function comparable to np.dot(x,x).

distance

Autodiff'ed function comparable to np.linalg.norm(x-y).

distanceSquared

Autodiff'ed function comparable to np.dot(x-y,x-y).

unit

Autodiff'ed function comparable to x/norm(x).

cross

Autodiff'ed function comparable to np.cross(x,y).

interpolate

Autodiff'ed function comparable to (1-u)*a+u*b.

class klampt.math.autodiff.math_ad.ShapedDot(shape1=None, shape2=None)[source]

Bases: ADFunctionInterface

This function is used to do matrix-vector products, which are by normally not supported by the dot function since all arguments are flattened 1D arrays. This function reshapes either the first or second arguments into a 2D array before calling dot. You must specify the array shape upon instantiation.

n_args()[source]

Returns the number of arguments.

n_in(arg)[source]

Returns the number of entries in argument #arg. If 1, this can either be a 1-D vector or a scalar. If -1, the function can accept a variable sized argument.

n_out()[source]

Returns the number of entries in the output of the function. If -1, this can output a variable sized argument.

eval(x, y)[source]

Evaluates the application of the function to the given (instantiated) arguments.

Parameters:

args (list) – a list of arguments, which are either ndarrays or scalars.

derivative(arg, x, y)[source]

Returns the Jacobian of the function w.r.t. argument #arg.

Parameters:
  • arg (int) – A value from 0,…,self.n_args()-1 indicating that we wish to take \(df/dx_{arg}\).

  • args (list of ndarrays) – arguments for the function.

Returns:

A numpy array of shape (self.n_out(),self.n_in(arg)). Keep in mind that even if the argument or result is a scalar, this needs to be a 2D array.

If the derivative is not implemented, raise a NotImplementedError.

If the derivative is zero, can just return 0 (the integer) regardless of the size of the result.

Return type:

ndarray

jvp(arg, darg, x, y)[source]

Performs a Jacobian-vector product for argument #arg.

Parameters:
  • arg (int) – A value from 0,…,self.n_args()-1 indicating that we wish to calculate df/dx_arg * darg.

  • darg (ndarray) – the derivative of x_arg w.r.t some other parameter. Must have darg.shape = (self.n_in(arg),).

  • args (list of ndarrays) – arguments for the function.

Returns:

A numpy array of length self.n_out()

If the derivative is not implemented, raise a NotImplementedError.

Return type:

ndarray

gen_derivative(arg, x, y)[source]

Generalized derivative that allows higher-order derivatives to be taken.

Parameters:
  • arg (list) – Indicates the order of derivatives to be taken. For example, to take the 2nd derivative w.r.t. x0,x1, arg = [0,1] should be specified.

  • args (list of ndarrays) – arguments for the function.

Returns:

A tensor of shape (n_out,n_in(arg[0]),..., n_in(arg[-1]).

If the generalized derivative is not implemented, raise a NotImplementedError.

If the generalized derivative is zero, can just return 0 (the integer) regardless of the size of the result.

Return type:

ndarray

klampt.math.autodiff.math_ad.exp(*args) = <klampt.math.autodiff.math_ad._ADExp object>

Autodiff’ed function comparable to np.exp. First derivative is implemented.

klampt.math.autodiff.math_ad.log(*args) = <klampt.math.autodiff.math_ad._ADLog object>

Autodiff’ed function comparable to np.log. First derivative is implemented.

klampt.math.autodiff.math_ad.sqrt(*args) = <klampt.math.autodiff.math_ad._ADSqrt object>

Autodiff’ed function comparable to np.sqrt. First derivative is implemented.

klampt.math.autodiff.math_ad.sin(*args) = <klampt.math.autodiff.math_ad._ADSin object>

Autodiff’ed function comparable to np.sin. All derivatives are implemented.

klampt.math.autodiff.math_ad.cos(*args) = <klampt.math.autodiff.math_ad._ADCos object>

Autodiff’ed function comparable to np.cos. All derivatives are implemented.

klampt.math.autodiff.math_ad.dot(*args) = <klampt.math.autodiff.math_ad._ADDot object>

Autodiff’ed function comparable to np.dot. All derivatives are implemented.

klampt.math.autodiff.math_ad.linear(A, x)[source]

Autodiff’ed function comparable to np.dot(A,x). A must be a constant, 2D np.array. x may be an expression.

klampt.math.autodiff.math_ad.quadratric(A, x)[source]

Autodiff’ed function comparable to np.dot(x,np.dot(A,x)). A must be a constant, 2D np.array. x may be an expression.

klampt.math.autodiff.math_ad.bilinear(x, A, y)[source]

Autodiff’ed function comparable to np.dot(x,np.dot(A,y)). A must be a constant, 2D np.array. x and y may be expressions.

klampt.math.autodiff.math_ad.norm(*args) = <klampt.math.autodiff.ad._ad_norm object>

Autodiff’ed function comparable to np.linalg.norm. First derivative is implemented.

klampt.math.autodiff.math_ad.normSquared(*args) = <klampt.math.autodiff.ad._ad_normSquared object>

Autodiff’ed function comparable to np.dot(x,x). All derivatives are implemented.

klampt.math.autodiff.math_ad.distance(*args) = <klampt.math.autodiff.math_ad._ADDistanceL2 object>

Autodiff’ed function comparable to np.linalg.norm(x-y). First derivative is implemented.

klampt.math.autodiff.math_ad.distanceSquared(*args) = <klampt.math.autodiff.math_ad._ADDistanceSquared object>

Autodiff’ed function comparable to np.dot(x-y,x-y). All derivatives are implemented.

klampt.math.autodiff.math_ad.unit(*args) = <klampt.math.autodiff.ad._ad_unit object>

Autodiff’ed function comparable to x/norm(x). First derivative is implemented.

klampt.math.autodiff.math_ad.cross(*args) = <klampt.math.autodiff.ad._ad_cross object>

Autodiff’ed function comparable to np.cross(x,y). First derivative is implemented. Some 2nd derivatives are implemented.

klampt.math.autodiff.math_ad.interpolate(*args) = <klampt.math.autodiff.ad._ad_interpolate object>

Autodiff’ed function comparable to (1-u)*a+u*b. First derivatives is implemented.