klampt.math.autodiff.trajectory_ad module

Klampt trajectory AD functions:

Function

Derivative

Notes

hermite

Y

hermite(x1,v1,x2,v2,u) -> R^n

GeodesicInterpolate

1(u)

ginterp[geodesic](a,b,u) -> R^n

GeodesicDistance

1

gdist[geodesic](a,b) -> R

TrajectoryEval

1

eval[Trajectory,endBehavior](t) -> R^n

Trajectory

1

trajectory[n,end](ts,xs,t) -> R^n

Module summary

hermite

Autodiff'ed version of the klampt.math.spline.hermite() function.

GeodesicInterpolate(geodesic)

Autodiff wrapper of geodesic.interpolate(a,b,u).

GeodesicDistance(geodesic)

Autodiff wrapper of geodesic.distance(a,b).

TrajectoryEval(traj[, endBehavior])

Autodiff wrapper of traj.eval(t).

Trajectory(n_or_robot[, endBehavior])

Autodiff piecewise linear interpolation traj(times,milestone_stack,t).

klampt.math.autodiff.trajectory_ad.hermite(*args) = <klampt.math.autodiff.ad._ad_trajectory.hermite object>

Autodiff’ed version of the klampt.math.spline.hermite() function. Takes Arguments (x1,v1,x2,v2,u) defining a Hermite curve with endpoints x1,x2 and velocities v1,v2, and returns the interpolant at parameter u in [0,1].

class klampt.math.autodiff.trajectory_ad.GeodesicInterpolate(geodesic)[source]

Bases: ADFunctionInterface

Autodiff wrapper of geodesic.interpolate(a,b,u).

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(a, b, u)[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.

jvp(arg, darg, a, b, u)[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

class klampt.math.autodiff.trajectory_ad.GeodesicDistance(geodesic)[source]

Bases: ADFunctionInterface

Autodiff wrapper of geodesic.distance(a,b).

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(a, b)[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.

jvp(arg, darg, a, b)[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

class klampt.math.autodiff.trajectory_ad.TrajectoryEval(traj, endBehavior='halt')[source]

Bases: ADFunctionInterface

Autodiff wrapper of traj.eval(t).

Parameters:
  • traj (Trajectory) – the trajectory to evaluate. Can be any Trajectory subclass.

  • endBehavior (string) – how to evaluate out-of-domain times. Can be ‘halt’ or ‘loop’.

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(t)[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, t)[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, t)[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

class klampt.math.autodiff.trajectory_ad.Trajectory(n_or_robot, endBehavior='halt')[source]

Bases: ADFunctionInterface

Autodiff piecewise linear interpolation traj(times,milestone_stack,t). The dimensionality or a robot must be provided on initialization.

milestone_stack is a flattened array of the trajectory’s milestones.

Also, t can be either a scalar or an array of times. Providing an array of times is faster than calling this repeatedly for multiple times.

Parameters:
  • n_or_robot (int or RobotModel) – the dimension of the state, or the robot. In this case the milestones must be robot configurations.

  • endBehavior (string) – how to evaluate out-of-domain times. Can be ‘halt’ or ‘loop’.

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(ts, xs, t)[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.

jvp(arg, darg, ts, xs, t)[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