klampt.math.autodiff.pytorch module¶
-
class
klampt.math.autodiff.pytorch.
ADModule
[source]¶ Bases:
torch.autograd.function.Function
Converts a Klamp’t autodiff function call or function instance to a PyTorch Function. The class must be created with the terminal symbols corresponding to the PyTorch arguments to which this is called.
-
static
backward
(ctx, grad)[source]¶ Defines a formula for differentiating the operation.
This function is to be overridden by all subclasses.
It must accept a context
ctx
as the first argument, followed by as many outputs didforward()
return, and it should return as many tensors, as there were inputs toforward()
. Each argument is the gradient w.r.t the given output, and each returned value should be the gradient w.r.t. the corresponding input.The context can be used to retrieve tensors saved during the forward pass. It also has an attribute
ctx.needs_input_grad
as a tuple of booleans representing whether each input needs gradient. E.g.,backward()
will havectx.needs_input_grad[0] = True
if the first input toforward()
needs gradient computated w.r.t. the output.
-
static
forward
(ctx, func, terminals, *args)[source]¶ Performs the operation.
This function is to be overridden by all subclasses.
It must accept a context ctx as the first argument, followed by any number of arguments (tensors or other types).
The context can be used to store tensors that can be then retrieved during the backward pass.
-
static
-
class
klampt.math.autodiff.pytorch.
TorchModuleFunction
(module)[source]¶ Bases:
klampt.math.autodiff.ad.ADFunctionInterface
Converts a PyTorch function to a Klamp’t autodiff function class.
-
derivative
(arg, *args)[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
-
eval
(*args)[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, *args)[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
-
-
klampt.math.autodiff.pytorch.
ad_to_torch
(func, terminals=None)[source]¶ Converts a Klamp’t autodiff function call or function instance to a PyTorch Function. If terminals is provided, this is the list of arguments that PyTorch will expect. Otherwise, the variables in the expression will be automatically determined by the forward traversal order.