pydrake.math

Bindings for //math.

class pydrake.math.BarycentricMesh

Represents a multi-linear function (from vector inputs to vector outputs) by interpolating between points on a mesh using (triangular) barycentric interpolation.

For a technical description of barycentric interpolation, see e.g. Remi Munos and Andrew Moore, “Barycentric Interpolators for Continuous Space and Time Reinforcement Learning”, NIPS 1998

Template parameter T:
The vector element type, which must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
Eval(self: pydrake.math.BarycentricMesh, arg0: numpy.ndarray[float64[m, n], flags.f_contiguous], arg1: numpy.ndarray[float64[m, 1]]) → numpy.ndarray[float64[m, 1]]

Returns the function evaluated at input.

EvalBarycentricWeights(self: pydrake.math.BarycentricMesh, arg0: numpy.ndarray[float64[m, 1]]) → Tuple[numpy.ndarray[int32[m, 1]], numpy.ndarray[float64[m, 1]]]

Writes the mesh indices used for interpolation to mesh_indices, and the interpolating coefficients to weights. Inputs that are outside the bounding box of the input_grid are interpolated as though they were projected (elementwise) to the closest face of the defined mesh.

Parameter input:
must be a vector of length get_num_inputs().
Parameter mesh_indices:
is a pointer to a vector of length get_num_interpolants().
Parameter weights:
is a vector of coefficients (which sum to 1) of length get_num_interpolants().
MeshValuesFrom(self: pydrake.math.BarycentricMesh, arg0: Callable[[numpy.ndarray[float64[m, 1]]], numpy.ndarray[float64[m, 1]]]) → numpy.ndarray[float64[m, n]]

Evaluates vector_func at all input mesh points and extracts the mesh value matrix that should be used to approximate the function with this barycentric interpolation.

MatrixXd mesh_values = bary.MeshValuesFrom(
    [](const auto& x) { return Vector1d(std::sin(x[0])); });
__init__(self: pydrake.math.BarycentricMesh, arg0: List[Set[float]]) → None

Constructs the mesh.

get_all_mesh_points(self: pydrake.math.BarycentricMesh) → numpy.ndarray[float64[m, n]]

Returns a matrix with all of the mesh points, one per column.

get_input_grid(self: pydrake.math.BarycentricMesh) → List[Set[float]]
get_input_size(self: pydrake.math.BarycentricMesh) → int
get_mesh_point(self: pydrake.math.BarycentricMesh, arg0: int) → numpy.ndarray[float64[m, 1]]

Returns the position of a mesh point in the input space referenced by its scalar index to point.

Parameter index:
must be in [0, get_num_mesh_points).
get_num_interpolants(self: pydrake.math.BarycentricMesh) → int
get_num_mesh_points(self: pydrake.math.BarycentricMesh) → int
pydrake.math.ComputeBasisFromAxis(axis_index: int, axis_W: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]

Creates a right-handed local basis from a given axis. Defines two other arbitrary axes such that the basis is orthonormal. The basis is R_WL, where W is the frame in which the input axis is expressed and L is a local basis such that v_W = R_WL * v_L.

Parameter axis_index:
The index of the axis (in the range [0,2]), with 0 corresponding to the x-axis, 1 corresponding to the y-axis, and z-corresponding to the z-axis.
Parameter axis_W:
The vector defining the basis’s given axis expressed in frame W. The vector need not be a unit vector: this routine will normalize it.
Returns R_WL:
The computed basis.
Raises:
  • RuntimeError if the norm of axis_W is within 1e-10 to zero or
  • axis_index does not lie in the range [0,2].
class pydrake.math.RigidTransform

This class represents a proper rigid transform between two frames which can be regarded in two ways. It can be regarded as a distance-preserving linear operator that can rotate and/or translate a rigid body without changing its shape or size (rigid) and without mirroring/reflecting the body (proper), e.g., it can add one position vector to another and express the result in a particular basis as p_AoQ_A = X_AB * p_BoQ_B (Q is any point). Alternately, a rigid transform describes the pose between two frames A and B (i.e., the relative orientation and position of A to B). Herein, the terms rotation/orientation and translation/position are used interchangeably. The class stores a RotationMatrix that relates right-handed orthogonal unit vectors Ax, Ay, Az fixed in frame A to right-handed orthogonal unit vectors Bx, By, Bz fixed in frame B. The class also stores a position vector from Ao (the origin of frame A) to Bo (the origin of frame B). The position vector is expressed in frame A. The monogram notation for the transform relating frame A to B is X_AB. The monogram notation for the rotation matrix relating A to B is R_AB. The monogram notation for the position vector from Ao to Bo is p_AoBo_A. See multibody_quantities for monogram notation for dynamics.

Note

This class does not store the frames associated with the transform and cannot enforce correct usage of this class. For example, it makes sense to multiply RigidTransforms as X_AB * X_BC, but not X_AB * X_CB.

Note

This class is not a 4x4 transformation matrix – even though its operator*() methods act like 4x4 matrix multiplication. Instead, this class contains a rotation matrix class as well as a 3x1 position vector. To form a 4x4 matrix, use GetAsMatrix(). GetAsIsometry() is treated similarly.

Note

An isometry is sometimes regarded as synonymous with rigid transform.

Authors:
Paul Mitiguy (2018) Original author.
Authors:
Drake team (see https://drake.mit.edu/credits).
Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.
GetAsIsometry3(self: pydrake.math.RigidTransform) → pydrake.common.eigen_geometry.Isometry3

Returns the isometry in ℜ³ that is equivalent to a RigidTransform.

GetAsMatrix34(self: pydrake.math.RigidTransform) → numpy.ndarray[float64[3, 4]]

Returns the 3x4 matrix associated with this RigidTransform, i.e., X_AB.

┌                ┐
 │ R_AB  p_AoBo_A │
 └                ┘
GetAsMatrix4(self: pydrake.math.RigidTransform) → numpy.ndarray[float64[4, 4]]

Returns the 4x4 matrix associated with this RigidTransform, i.e., X_AB.

┌                ┐
 │ R_AB  p_AoBo_A │
 │                │
 │   0      1     │
 └                ┘
Identity() → pydrake.math.RigidTransform
SetFromIsometry3(self: pydrake.math.RigidTransform, pose: pydrake.common.eigen_geometry.Isometry3) → None

Sets this RigidTransform from an Eigen Isometry3.

Parameter pose:
Isometry3 that contains an allegedly valid rotation matrix R_AB and also contains a position vector p_AoBo_A from frame A’s origin to frame B’s origin. p_AoBo_A must be expressed in frame A.
Raises:
  • RuntimeError in debug builds if R_AB is not a proper orthonormal
  • 3x3 rotation matrix.

Note

no attempt is made to orthogonalize the 3x3 rotation matrix part of pose. As needed, use RotationMatrix::ProjectToRotationMatrix().

SetIdentity(self: pydrake.math.RigidTransform) → pydrake.math.RigidTransform

Sets this RigidTransform so it corresponds to aligning the two frames so unit vectors Ax = Bx, Ay = By, Az = Bz and point Ao is coincident with Bo. Hence, this RigidTransform contains a 3x3 identity matrix and a zero position vector.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.math.RigidTransform) -> None
  2. __init__(self: pydrake.math.RigidTransform, R: drake::math::RotationMatrix<double>, p: numpy.ndarray[float64[3, 1]]) -> None

Constructs a RigidTransform from a rotation matrix and a position vector.

Parameter R:
rotation matrix relating frames A and B (e.g., R_AB).
Parameter p:
position vector from frame A’s origin to frame B’s origin, expressed in frame A. In monogram notation p is denoted p_AoBo_A.
  1. __init__(self: pydrake.math.RigidTransform, rpy: drake::math::RollPitchYaw<double>, p: numpy.ndarray[float64[3, 1]]) -> None

Constructs a RigidTransform from a RollPitchYaw and a position vector.

Parameter rpy:
a RollPitchYaw which is a Space-fixed (extrinsic) X-Y-Z rotation with “roll-pitch-yaw” angles [r, p, y] or equivalently a Body- fixed (intrinsic) Z-Y-X rotation with “yaw-pitch-roll” angles [y, p, r].

See also

RotationMatrix::RotationMatrix(const RollPitchYaw<T>&)

Parameter p:
position vector from frame A’s origin to frame B’s origin, expressed in frame A. In monogram notation p is denoted p_AoBo_A.
  1. __init__(self: pydrake.math.RigidTransform, quaternion: pydrake.common.eigen_geometry.Quaternion, p: numpy.ndarray[float64[3, 1]]) -> None

Constructs a RigidTransform from a Quaternion and a position vector.

Parameter quaternion:
a non-zero, finite quaternion which may or may not have unit length [i.e., quaternion.norm() does not have to be 1].
Parameter p:
position vector from frame A’s origin to frame B’s origin, expressed in frame A. In monogram notation p is denoted p_AoBo_A.
Raises:
  • RuntimeError in debug builds if the rotation matrix that is built
  • from quaternion is invalid.

See also

RotationMatrix::RotationMatrix(const Eigen::Quaternion<T>&)

  1. __init__(self: pydrake.math.RigidTransform, theta_lambda: pydrake.common.eigen_geometry.AngleAxis, p: numpy.ndarray[float64[3, 1]]) -> None

Constructs a RigidTransform from a AngleAxis and a position vector.

Parameter theta_lambda:
an Eigen::AngleAxis whose associated axis (vector direction herein called lambda) is non-zero and finite, but which may or may not have unit length [i.e., lambda.norm() does not have to be 1].
Parameter p:
position vector from frame A’s origin to frame B’s origin, expressed in frame A. In monogram notation p is denoted ``p_AoBo_A
Raises:
  • RuntimeError in debug builds if the rotation matrix that is built
  • from theta_lambda` is invalid.

See also

RotationMatrix::RotationMatrix(const Eigen::AngleAxis<T>&)

  1. __init__(self: pydrake.math.RigidTransform, R: drake::math::RotationMatrix<double>) -> None

Constructs a RigidTransform with a given RotationMatrix and a zero position vector.

Parameter R:
rotation matrix relating frames A and B (e.g., R_AB).
  1. __init__(self: pydrake.math.RigidTransform, p: numpy.ndarray[float64[3, 1]]) -> None

Constructs a RigidTransform with an identity RotationMatrix and a given position vector ‘p’.

Parameter p:
position vector from frame A’s origin to frame B’s origin, expressed in frame A. In monogram notation p is denoted p_AoBo_A.
  1. __init__(self: pydrake.math.RigidTransform, pose: pydrake.common.eigen_geometry.Isometry3) -> None

Constructs a RigidTransform from an Eigen Isometry3.

Parameter pose:
Isometry3 that contains an allegedly valid rotation matrix R_AB and also contains a position vector p_AoBo_A from frame A’s origin to frame B’s origin. p_AoBo_A must be expressed in frame A.
Raises:
  • RuntimeError in debug builds if R_AB is not a proper orthonormal
  • 3x3 rotation matrix.

Note

no attempt is made to orthogonalize the 3x3 rotation matrix part of pose. As needed, use RotationMatrix::ProjectToRotationMatrix().

inverse(self: pydrake.math.RigidTransform) → pydrake.math.RigidTransform
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.math.RigidTransform, other: pydrake.math.RigidTransform) -> pydrake.math.RigidTransform

Calculates this RigidTransform X_AB multiplied by other RigidTransform X_BC.

Parameter other:
RigidTransform that post-multiplies this.
Returns X_AC:
= X_AB * X_BC
  1. multiply(self: pydrake.math.RigidTransform, p_BoQ_B: numpy.ndarray[float64[3, 1]]) -> numpy.ndarray[float64[3, 1]]

Calculates this RigidTransform X_AB multiplied by the position vector ‘p_BoQ_B` which is from Bo (B’s origin) to an arbitrary point Q.

Parameter p_BoQ_B:
position vector from Bo to Q, expressed in frame B.
Returns p_AoQ_A:
position vector from Ao to Q, expressed in frame A.
rotation(self: pydrake.math.RigidTransform) → drake::math::RotationMatrix<double>

Returns R_AB, the rotation matrix portion of this RigidTransform.

Returns R_AB:
the rotation matrix portion of this RigidTransform.
set(self: pydrake.math.RigidTransform, R: drake::math::RotationMatrix<double>, p: numpy.ndarray[float64[3, 1]]) → None

Sets this RigidTransform from a RotationMatrix and a position vector.

Parameter R:
rotation matrix relating frames A and B (e.g., R_AB).
Parameter p:
position vector from frame A’s origin to frame B’s origin, expressed in frame A. In monogram notation p is denoted p_AoBo_A.
set_rotation(self: pydrake.math.RigidTransform, R: drake::math::RotationMatrix<double>) → None

Sets the RotationMatrix portion of this RigidTransform.

Parameter R:
rotation matrix relating frames A and B (e.g., R_AB).
set_translation(self: pydrake.math.RigidTransform, p: numpy.ndarray[float64[3, 1]]) → None

Sets the position vector portion of this RigidTransform.

Parameter p:
position vector from Ao (frame A’s origin) to Bo (frame B’s origin) expressed in frame A. In monogram notation p is denoted p_AoBo_A.
translation(self: pydrake.math.RigidTransform) → numpy.ndarray[float64[3, 1]]

Returns p_AoBo_A, the position vector portion of this RigidTransform, i.e., position vector from Ao (frame A’s origin) to Bo (frame B’s origin).

class pydrake.math.RollPitchYaw
ToQuaternion(self: pydrake.math.RollPitchYaw) → pydrake.common.eigen_geometry.Quaternion

Returns a quaternion representation of this RollPitchYaw.

ToRotationMatrix(self: pydrake.math.RollPitchYaw) → drake::math::RotationMatrix<double>

Returns the RotationMatrix representation of this RollPitchYaw.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.math.RollPitchYaw, rpy: numpy.ndarray[float64[3, 1]]) -> None

Constructs a RollPitchYaw from a 3x1 array of angles.

Parameter rpy:
3x1 array with roll, pitch, yaw angles (units of radians).
Raises:RuntimeError in debug builds if !IsValid(rpy).
  1. __init__(self: pydrake.math.RollPitchYaw, roll: float, pitch: float, yaw: float) -> None

Constructs a RollPitchYaw from roll, pitch, yaw angles (radian units).

Parameter roll:
x-directed angle in SpaceXYZ rotation sequence.
Parameter pitch:
y-directed angle in SpaceXYZ rotation sequence.
Parameter yaw:
z-directed angle in SpaceXYZ rotation sequence.
Raises:
  • RuntimeError in debug builds if !IsValid(Vector3<T>(roll, pitch,
  • yaw)).
  1. __init__(self: pydrake.math.RollPitchYaw, R: drake::math::RotationMatrix<double>) -> None

Uses a RotationMatrix to construct a RollPitchYaw with roll-pitch-yaw angles [r, p, y] in the range <= r <= π, -π/2 <= p <= π/2, `-π <= y <= π``.

Parameter R:
a RotationMatrix.

Note

This new high-accuracy algorithm avoids numerical round-off issues encountered by some algorithms when pitch is within 1E-6 of π/2 or -π/2.

  1. __init__(self: pydrake.math.RollPitchYaw, quaternion: pydrake.common.eigen_geometry.Quaternion) -> None

Uses a Quaternion to construct a RollPitchYaw with roll-pitch-yaw angles [r, p, y] in the range <= r <= π, -π/2 <= p <= π/2, `-π <= y <= π``.

Parameter quaternion:
unit Quaternion.

Note

This new high-accuracy algorithm avoids numerical round-off issues encountered by some algorithms when pitch is within 1E-6 of π/2 or -π/2.

Raises:RuntimeError in debug builds if !IsValid(rpy).
pitch_angle(self: pydrake.math.RollPitchYaw) → float

Returns the pitch-angle underlying this RollPitchYaw.

roll_angle(self: pydrake.math.RollPitchYaw) → float

Returns the roll-angle underlying this RollPitchYaw.

vector(self: pydrake.math.RollPitchYaw) → numpy.ndarray[float64[3, 1]]

Returns the Vector3 underlying this RollPitchYaw.

yaw_angle(self: pydrake.math.RollPitchYaw) → float

Returns the yaw-angle underlying this RollPitchYaw.

class pydrake.math.RotationMatrix

This class represents a 3x3 rotation matrix between two arbitrary frames A and B and helps ensure users create valid rotation matrices. This class relates right-handed orthogonal unit vectors Ax, Ay, Az fixed in frame A to right-handed orthogonal unit vectors Bx, By, Bz fixed in frame B. The monogram notation for the rotation matrix relating A to B is R_AB. An example that gives context to this rotation matrix is v_A = R_AB * v_B, where v_B denotes an arbitrary vector v expressed in terms of Bx, By, Bz and v_A denotes vector v expressed in terms of Ax, Ay, Az. See multibody_quantities for monogram notation for dynamics. See orientation_discussion “a discussion on rotation matrices”.

Note

This class does not store the frames associated with a rotation matrix nor does it enforce strict proper usage of this class with vectors.

Note

When DRAKE_ASSERT_IS_ARMED is defined, several methods in this class do a validity check and throw an exception (RuntimeError) if the rotation matrix is invalid. When DRAKE_ASSERT_IS_ARMED is not defined, many of these validity checks are skipped (which helps improve speed). In addition, these validity tests are only performed for scalar types for which drake::scalar_predicate<T>::is_bool is True. For instance, validity checks are not performed when T is symbolic::Expression.

Authors:
Paul Mitiguy (2018) Original author.
Authors:
Drake team (see https://drake.mit.edu/credits).
Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.

Instantiated templates for the following kinds of T’s are provided:

  • double
  • AutoDiffXd
  • symbolic::Expression
Identity() → pydrake.math.RotationMatrix
ToQuaternion(self: pydrake.math.RotationMatrix) → pydrake.common.eigen_geometry.Quaternion
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.math.RotationMatrix) -> None

Constructs a 3x3 identity RotationMatrix – which corresponds to aligning two frames (so that unit vectors Ax = Bx, Ay = By, Az = Bz).

  1. __init__(self: pydrake.math.RotationMatrix, R: numpy.ndarray[float64[3, 3]]) -> None

Constructs a RotationMatrix from a Matrix3.

Parameter R:
an allegedly valid rotation matrix.
Raises:RuntimeError in debug builds if R fails IsValid(R).
  1. __init__(self: pydrake.math.RotationMatrix, quaternion: pydrake.common.eigen_geometry.Quaternion) -> None

Constructs a RotationMatrix from an Eigen::Quaternion.

Parameter quaternion:
a non-zero, finite quaternion which may or may not have unit length [i.e., quaternion.norm() does not have to be 1].
Raises:
  • RuntimeError in debug builds if the rotation matrix R that is
  • built from quaternion fails IsValid(R). For example, an
  • exception is thrown if quaternion is zero or contains a NaN or
  • infinity.

Note

This method has the effect of normalizing its quaternion argument, without the inefficiency of the square-root associated with normalization.

  1. __init__(self: pydrake.math.RotationMatrix, rpy: pydrake.math.RollPitchYaw) -> None

Constructs a RotationMatrix from an RollPitchYaw. In other words, makes the RotationMatrix for a Space-fixed (extrinsic) X-Y-Z rotation by “roll-pitch-yaw” angles [r, p, y], which is equivalent to a Body-fixed (intrinsic) Z-Y-X rotation by “yaw-pitch-roll” angles [y, p, r].

Parameter rpy:
radian measures of three angles [roll, pitch, yaw].
Parameter rpy:
a RollPitchYaw which is a Space-fixed (extrinsic) X-Y-Z rotation with “roll-pitch-yaw” angles [r, p, y] or equivalently a Body- fixed (intrinsic) Z-Y-X rotation with “yaw-pitch-roll” angles [y, p, r].

Note

Denoting roll r, pitch p, yaw y, this method returns a rotation matrix R_AD equal to the matrix multiplication shown below.

⎡cos(y) -sin(y)  0⎤   ⎡ cos(p)  0  sin(p)⎤   ⎡1      0        0 ⎤
R_AD = ⎢sin(y)  cos(y)  0⎥ * ⎢     0   1      0 ⎥ * ⎢0  cos(r)  -sin(r)⎥
       ⎣    0       0   1⎦   ⎣-sin(p)  0  cos(p)⎦   ⎣0  sin(r)   cos(r)⎦
     =       R_AB          *        R_BC          *        R_CD

Note

In this discussion, A is the Space frame and D is the Body frame. One way to visualize this rotation sequence is by introducing intermediate frames B and C (useful constructs to understand this rotation sequence). Initially, the frames are aligned so Di = Ci = Bi = Ai (i = x, y, z). Then D is subjected to successive right-handed rotations relative to A.

  • 1st rotation R_CD: Frame D rotates relative to frames C, B, A by a

roll angle r about Dx = Cx. Note: D and C are no longer aligned.

  • 2nd rotation R_BC: Frames D, C (collectively – as if welded together)

rotate relative to frame B, A by a pitch angle p about Cy = By. Note: C and B are no longer aligned.

  • 3rd rotation R_AB: Frames D, C, B (collectively – as if welded)

rotate relative to frame A by a roll angle y about Bz = Az. Note: B and A are no longer aligned.

inverse(self: pydrake.math.RotationMatrix) → pydrake.math.RotationMatrix
matrix(self: pydrake.math.RotationMatrix) → numpy.ndarray[float64[3, 3]]

Returns the Matrix3 underlying a RotationMatrix.

multiply(self: pydrake.math.RotationMatrix, arg0: pydrake.math.RotationMatrix) → pydrake.math.RotationMatrix

Calculates this rotation matrix R_AB multiplied by other rotation matrix R_BC, returning the composition R_AB * R_BC.

Parameter other:
RotationMatrix that post-multiplies this.
Returns:rotation matrix that results from this multiplied by other.

Note

It is possible (albeit improbable) to create an invalid rotation matrix by accumulating round-off error with a large number of multiplies.

pydrake.math.abs(*args, **kwargs)

Overloaded function.

  1. abs(arg0: float) -> float
  2. abs(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. abs(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.acos(*args, **kwargs)

Overloaded function.

  1. acos(arg0: float) -> float
  2. acos(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. acos(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.asin(*args, **kwargs)

Overloaded function.

  1. asin(arg0: float) -> float
  2. asin(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. asin(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.atan(*args, **kwargs)

Overloaded function.

  1. atan(arg0: float) -> float
  2. atan(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.atan2(*args, **kwargs)

Overloaded function.

  1. atan2(y: float, x: float) -> float
  2. atan2(arg0: pydrake.autodiffutils.AutoDiffXd, arg1: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. atan2(arg0: pydrake.symbolic.Expression, arg1: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.ceil(*args, **kwargs)

Overloaded function.

  1. ceil(arg0: float) -> float
  2. ceil(arg0: pydrake.autodiffutils.AutoDiffXd) -> float
  3. ceil(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.cos(*args, **kwargs)

Overloaded function.

  1. cos(arg0: float) -> float
  2. cos(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. cos(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.cosh(*args, **kwargs)

Overloaded function.

  1. cosh(arg0: float) -> float
  2. cosh(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. cosh(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.exp(*args, **kwargs)

Overloaded function.

  1. exp(arg0: float) -> float
  2. exp(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. exp(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.floor(*args, **kwargs)

Overloaded function.

  1. floor(arg0: float) -> float
  2. floor(arg0: pydrake.autodiffutils.AutoDiffXd) -> float
  3. floor(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.log(*args, **kwargs)

Overloaded function.

  1. log(arg0: float) -> float
  2. log(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. log(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.max(*args, **kwargs)

Overloaded function.

  1. max(arg0: float, arg1: float) -> float
  2. max(arg0: pydrake.autodiffutils.AutoDiffXd, arg1: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. max(arg0: pydrake.symbolic.Expression, arg1: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.min(*args, **kwargs)

Overloaded function.

  1. min(arg0: float, arg1: float) -> float
  2. min(arg0: pydrake.autodiffutils.AutoDiffXd, arg1: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. min(arg0: pydrake.symbolic.Expression, arg1: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.pow(*args, **kwargs)

Overloaded function.

  1. pow(arg0: float, arg1: float) -> float
  2. pow(arg0: pydrake.autodiffutils.AutoDiffXd, arg1: int) -> pydrake.autodiffutils.AutoDiffXd
  3. pow(arg0: pydrake.symbolic.Expression, arg1: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.sin(*args, **kwargs)

Overloaded function.

  1. sin(arg0: float) -> float
  2. sin(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. sin(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.sinh(*args, **kwargs)

Overloaded function.

  1. sinh(arg0: float) -> float
  2. sinh(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. sinh(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.sqrt(*args, **kwargs)

Overloaded function.

  1. sqrt(arg0: float) -> float
  2. sqrt(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. sqrt(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.tan(*args, **kwargs)

Overloaded function.

  1. tan(arg0: float) -> float
  2. tan(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. tan(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.tanh(*args, **kwargs)

Overloaded function.

  1. tanh(arg0: float) -> float
  2. tanh(arg0: pydrake.autodiffutils.AutoDiffXd) -> pydrake.autodiffutils.AutoDiffXd
  3. tanh(arg0: pydrake.symbolic.Expression) -> pydrake.symbolic.Expression
pydrake.math.wrap_to(value: float, low: float, high: float) → float

For variables that are meant to be periodic, (e.g. over a 2π interval), wraps value into the interval [low, high). Precisely, wrap_to returns: value + k*(high-low) for the unique integer value k that lands the output in the desired interval. low and high must be finite, and low < high.