pydrake.autodiffutils

Bindings for Eigen AutoDiff Scalars

class pydrake.autodiffutils.AutoDiffXd
abs(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
acos(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
arccos()

acos(self: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd

arcsin()

asin(self: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd

arctan2()

atan2(self: pydrake.autodiffutils.AutoDiffXd, arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd

asin(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
atan2(self: pydrake.autodiffutils.AutoDiffXd, arg0: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
ceil(self: pydrake.autodiffutils.AutoDiffXd) → float
cos(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
cosh(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
derivatives(self: pydrake.autodiffutils.AutoDiffXd) → numpy.ndarray[float64[m, 1]]
exp(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
floor(self: pydrake.autodiffutils.AutoDiffXd) → float
inv(self: numpy.ndarray[object[m, n]]) → numpy.ndarray[object[m, n]]
log(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
max(self: pydrake.autodiffutils.AutoDiffXd, arg0: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
min(self: pydrake.autodiffutils.AutoDiffXd, arg0: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
pow(self: pydrake.autodiffutils.AutoDiffXd, arg0: float) → pydrake.autodiffutils.AutoDiffXd
sin(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
sinh(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
sqrt(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
tan(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
tanh(self: pydrake.autodiffutils.AutoDiffXd) → pydrake.autodiffutils.AutoDiffXd
value(self: pydrake.autodiffutils.AutoDiffXd) → float
pydrake.autodiffutils.autoDiffToGradientMatrix(autodiff_matrix: numpy.ndarray[object[m, n]]) → numpy.ndarray[float64[m, n]]
pydrake.autodiffutils.autoDiffToValueMatrix(autodiff_matrix: numpy.ndarray[object[m, n]]) → numpy.ndarray[float64[m, n]]
pydrake.autodiffutils.initializeAutoDiff(mat: numpy.ndarray[float64[m, n]], num_derivatives: int = -1, deriv_num_start: int = 0) → numpy.ndarray[object[m, n]]

Initialize a single autodiff matrix given the corresponding value matrix.

Create autodiff matrix that matches mat in size with derivatives of compile time size Nq and runtime size num_derivatives. Set its values to be equal to val, and for each element i of auto_diff_matrix, set derivative number deriv_num_start + i to one (all other derivatives set to zero).

Parameter mat:
‘regular’ matrix of values
Parameter num_derivatives:
the size of the derivatives vector $*Default:* the size of mat
Parameter deriv_num_start:
starting index into derivative vector (i.e. element deriv_num_start in derivative vector corresponds to mat(0, 0)).
Default: 0
$Returns:

AutoDiff matrix

pydrake.autodiffutils.initializeAutoDiffTuple(*args)

Given a series of array_like input arguments, create a tuple of corresponding AutoDiff matrices with values equal to the input matrices and properly initialized derivative vectors.

The size of the derivative vector of each element of the matrices in the output tuple will be the same, and will equal the sum of the number of elements of the matrices in args.

The 0th element of the derivative vectors will correspond to the derivative with respect to the 0th element of the first argument. Subsequent derivative vector elements correspond first to subsequent elements of the first input argument (traversed first by row, then by column), and so on for subsequent arguments.

This is a pythonic implementation of drake::math::initializeAutoDiffTuple in C++.