pydrake.common.eigen_geometry

Bindings for Eigen geometric types.

class pydrake.common.eigen_geometry.AngleAxis

Bindings for Eigen::AngleAxis<>.

Note

This class is templated; see AngleAxis_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.AngleAxis) -> None

  2. __init__(self: pydrake.common.eigen_geometry.AngleAxis, angle: float, axis: numpy.ndarray[numpy.float64[3, 1]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.AngleAxis, quaternion: pydrake.common.eigen_geometry.Quaternion) -> None

  4. __init__(self: pydrake.common.eigen_geometry.AngleAxis, rotation: numpy.ndarray[numpy.float64[3, 3]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.AngleAxis, other: pydrake.common.eigen_geometry.AngleAxis) -> None

angle(self: pydrake.common.eigen_geometry.AngleAxis) float
axis(self: pydrake.common.eigen_geometry.AngleAxis) numpy.ndarray[numpy.float64[3, 1]]
template cast

Instantiations: cast[float], cast[AutoDiffXd], cast[Expression]

cast[AutoDiffXd](self: pydrake.common.eigen_geometry.AngleAxis) Eigen::AngleAxis<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> > >

Cast to desired scalar type.

cast[Expression](self: pydrake.common.eigen_geometry.AngleAxis) Eigen::AngleAxis<drake::symbolic::Expression>

Cast to desired scalar type.

cast[float](self: pydrake.common.eigen_geometry.AngleAxis) pydrake.common.eigen_geometry.AngleAxis

Cast to desired scalar type.

static Identity() pydrake.common.eigen_geometry.AngleAxis
inverse(self: pydrake.common.eigen_geometry.AngleAxis) pydrake.common.eigen_geometry.AngleAxis
multiply(self: pydrake.common.eigen_geometry.AngleAxis, other: pydrake.common.eigen_geometry.AngleAxis) pydrake.common.eigen_geometry.Quaternion
quaternion(self: pydrake.common.eigen_geometry.AngleAxis) pydrake.common.eigen_geometry.Quaternion
rotation(self: pydrake.common.eigen_geometry.AngleAxis) numpy.ndarray[numpy.float64[3, 3]]
set_angle(self: pydrake.common.eigen_geometry.AngleAxis, angle: float) None
set_axis(self: pydrake.common.eigen_geometry.AngleAxis, axis: numpy.ndarray[numpy.float64[3, 1]]) None
set_quaternion(self: pydrake.common.eigen_geometry.AngleAxis, q: pydrake.common.eigen_geometry.Quaternion) None
set_rotation(self: pydrake.common.eigen_geometry.AngleAxis, rotation: numpy.ndarray[numpy.float64[3, 3]]) None
template pydrake.common.eigen_geometry.AngleAxis_

Instantiations: AngleAxis_[float], AngleAxis_[AutoDiffXd], AngleAxis_[Expression]

class pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]

Bindings for Eigen::AngleAxis<>.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) -> None

  2. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], angle: pydrake.autodiffutils.AutoDiffXd, axis: numpy.ndarray[object[3, 1]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], quaternion: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) -> None

  4. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], rotation: numpy.ndarray[object[3, 3]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], other: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) -> None

angle(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
axis(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) numpy.ndarray[object[3, 1]]
template cast

Instantiations: cast[AutoDiffXd]

cast[AutoDiffXd](self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]

Cast to desired scalar type.

static Identity() pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]
inverse(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]
multiply(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], other: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]
quaternion(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]
rotation(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd]) numpy.ndarray[object[3, 3]]
set_angle(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], angle: pydrake.autodiffutils.AutoDiffXd) None
set_axis(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], axis: numpy.ndarray[object[3, 1]]) None
set_quaternion(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], q: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) None
set_rotation(self: pydrake.common.eigen_geometry.AngleAxis_[AutoDiffXd], rotation: numpy.ndarray[object[3, 3]]) None
class pydrake.common.eigen_geometry.AngleAxis_[Expression]

Bindings for Eigen::AngleAxis<>.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) -> None

  2. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], angle: pydrake.symbolic.Expression, axis: numpy.ndarray[object[3, 1]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], quaternion: pydrake.common.eigen_geometry.Quaternion_[Expression]) -> None

  4. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], rotation: numpy.ndarray[object[3, 3]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], other: pydrake.common.eigen_geometry.AngleAxis_[Expression]) -> None

angle(self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) pydrake.symbolic.Expression
axis(self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) numpy.ndarray[object[3, 1]]
template cast

Instantiations: cast[Expression]

cast[Expression](self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) pydrake.common.eigen_geometry.AngleAxis_[Expression]

Cast to desired scalar type.

static Identity() pydrake.common.eigen_geometry.AngleAxis_[Expression]
inverse(self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) pydrake.common.eigen_geometry.AngleAxis_[Expression]
multiply(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], other: pydrake.common.eigen_geometry.AngleAxis_[Expression]) pydrake.common.eigen_geometry.Quaternion_[Expression]
quaternion(self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) pydrake.common.eigen_geometry.Quaternion_[Expression]
rotation(self: pydrake.common.eigen_geometry.AngleAxis_[Expression]) numpy.ndarray[object[3, 3]]
set_angle(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], angle: pydrake.symbolic.Expression) None
set_axis(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], axis: numpy.ndarray[object[3, 1]]) None
set_quaternion(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], q: pydrake.common.eigen_geometry.Quaternion_[Expression]) None
set_rotation(self: pydrake.common.eigen_geometry.AngleAxis_[Expression], rotation: numpy.ndarray[object[3, 3]]) None
class pydrake.common.eigen_geometry.Isometry3

Provides bindings of Eigen::Isometry3<> that only admit SE(3) (no reflections).

Note

This class is templated; see Isometry3_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.Isometry3) -> None

  2. __init__(self: pydrake.common.eigen_geometry.Isometry3, matrix: numpy.ndarray[numpy.float64[4, 4]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.Isometry3, rotation: numpy.ndarray[numpy.float64[3, 3]], translation: numpy.ndarray[numpy.float64[3, 1]]) -> None

  4. __init__(self: pydrake.common.eigen_geometry.Isometry3, quaternion: Eigen::Quaternion<double, 0>, translation: numpy.ndarray[numpy.float64[3, 1]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.Isometry3, other: pydrake.common.eigen_geometry.Isometry3) -> None

template cast

Instantiations: cast[float], cast[AutoDiffXd], cast[Expression]

cast[AutoDiffXd](self: pydrake.common.eigen_geometry.Isometry3) Eigen::Transform<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, 3, 1, 0>

Cast to desired scalar type.

cast[Expression](self: pydrake.common.eigen_geometry.Isometry3) Eigen::Transform<drake::symbolic::Expression, 3, 1, 0>

Cast to desired scalar type.

cast[float](self: pydrake.common.eigen_geometry.Isometry3) pydrake.common.eigen_geometry.Isometry3

Cast to desired scalar type.

static Identity() pydrake.common.eigen_geometry.Isometry3
inverse(self: pydrake.common.eigen_geometry.Isometry3) pydrake.common.eigen_geometry.Isometry3
matrix(self: pydrake.common.eigen_geometry.Isometry3) numpy.ndarray[numpy.float64[4, 4]]
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3, other: pydrake.common.eigen_geometry.Isometry3) -> pydrake.common.eigen_geometry.Isometry3

RigidTransform multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3, position: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[3, 1]]

Position vector multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3, position: numpy.ndarray[numpy.float64[3, n]]) -> numpy.ndarray[numpy.float64[3, n]]

Position vector list multiplication

quaternion(self: pydrake.common.eigen_geometry.Isometry3) Eigen::Quaternion<double, 0>
rotation(self: pydrake.common.eigen_geometry.Isometry3) numpy.ndarray[numpy.float64[3, 3]]
set_matrix(self: pydrake.common.eigen_geometry.Isometry3, arg0: numpy.ndarray[numpy.float64[4, 4]]) None
set_quaternion(self: pydrake.common.eigen_geometry.Isometry3, arg0: Eigen::Quaternion<double, 0>) None
set_rotation(self: pydrake.common.eigen_geometry.Isometry3, arg0: numpy.ndarray[numpy.float64[3, 3]]) None
set_translation(self: pydrake.common.eigen_geometry.Isometry3, arg0: numpy.ndarray[numpy.float64[3, 1]]) None
translation(self: pydrake.common.eigen_geometry.Isometry3) numpy.ndarray[numpy.float64[3, 1]]
template pydrake.common.eigen_geometry.Isometry3_

Instantiations: Isometry3_[float], Isometry3_[AutoDiffXd], Isometry3_[Expression]

class pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]

Provides bindings of Eigen::Isometry3<> that only admit SE(3) (no reflections).

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) -> None

  2. __init__(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], matrix: numpy.ndarray[object[4, 4]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], rotation: numpy.ndarray[object[3, 3]], translation: numpy.ndarray[object[3, 1]]) -> None

  4. __init__(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], quaternion: Eigen::Quaternion<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, 0>, translation: numpy.ndarray[object[3, 1]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], other: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) -> None

template cast

Instantiations: cast[AutoDiffXd]

cast[AutoDiffXd](self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]

Cast to desired scalar type.

static Identity() pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]
inverse(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]
matrix(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) numpy.ndarray[object[4, 4]]
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], other: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) -> pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]

RigidTransform multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], position: numpy.ndarray[object[3, 1]]) -> numpy.ndarray[object[3, 1]]

Position vector multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], position: numpy.ndarray[object[3, n]]) -> numpy.ndarray[object[3, n]]

Position vector list multiplication

quaternion(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) Eigen::Quaternion<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, 0>
rotation(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) numpy.ndarray[object[3, 3]]
set_matrix(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], arg0: numpy.ndarray[object[4, 4]]) None
set_quaternion(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], arg0: Eigen::Quaternion<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, 0>) None
set_rotation(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], arg0: numpy.ndarray[object[3, 3]]) None
set_translation(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd], arg0: numpy.ndarray[object[3, 1]]) None
translation(self: pydrake.common.eigen_geometry.Isometry3_[AutoDiffXd]) numpy.ndarray[object[3, 1]]
class pydrake.common.eigen_geometry.Isometry3_[Expression]

Provides bindings of Eigen::Isometry3<> that only admit SE(3) (no reflections).

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.Isometry3_[Expression]) -> None

  2. __init__(self: pydrake.common.eigen_geometry.Isometry3_[Expression], matrix: numpy.ndarray[object[4, 4]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.Isometry3_[Expression], rotation: numpy.ndarray[object[3, 3]], translation: numpy.ndarray[object[3, 1]]) -> None

  4. __init__(self: pydrake.common.eigen_geometry.Isometry3_[Expression], quaternion: Eigen::Quaternion<drake::symbolic::Expression, 0>, translation: numpy.ndarray[object[3, 1]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.Isometry3_[Expression], other: pydrake.common.eigen_geometry.Isometry3_[Expression]) -> None

template cast

Instantiations: cast[Expression]

cast[Expression](self: pydrake.common.eigen_geometry.Isometry3_[Expression]) pydrake.common.eigen_geometry.Isometry3_[Expression]

Cast to desired scalar type.

static Identity() pydrake.common.eigen_geometry.Isometry3_[Expression]
inverse(self: pydrake.common.eigen_geometry.Isometry3_[Expression]) pydrake.common.eigen_geometry.Isometry3_[Expression]
matrix(self: pydrake.common.eigen_geometry.Isometry3_[Expression]) numpy.ndarray[object[4, 4]]
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3_[Expression], other: pydrake.common.eigen_geometry.Isometry3_[Expression]) -> pydrake.common.eigen_geometry.Isometry3_[Expression]

RigidTransform multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3_[Expression], position: numpy.ndarray[object[3, 1]]) -> numpy.ndarray[object[3, 1]]

Position vector multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Isometry3_[Expression], position: numpy.ndarray[object[3, n]]) -> numpy.ndarray[object[3, n]]

Position vector list multiplication

quaternion(self: pydrake.common.eigen_geometry.Isometry3_[Expression]) Eigen::Quaternion<drake::symbolic::Expression, 0>
rotation(self: pydrake.common.eigen_geometry.Isometry3_[Expression]) numpy.ndarray[object[3, 3]]
set_matrix(self: pydrake.common.eigen_geometry.Isometry3_[Expression], arg0: numpy.ndarray[object[4, 4]]) None
set_quaternion(self: pydrake.common.eigen_geometry.Isometry3_[Expression], arg0: Eigen::Quaternion<drake::symbolic::Expression, 0>) None
set_rotation(self: pydrake.common.eigen_geometry.Isometry3_[Expression], arg0: numpy.ndarray[object[3, 3]]) None
set_translation(self: pydrake.common.eigen_geometry.Isometry3_[Expression], arg0: numpy.ndarray[object[3, 1]]) None
translation(self: pydrake.common.eigen_geometry.Isometry3_[Expression]) numpy.ndarray[object[3, 1]]
class pydrake.common.eigen_geometry.Quaternion

Provides a unit quaternion binding of Eigen::Quaternion<>.

Note

This class is templated; see Quaternion_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.Quaternion) -> None

  2. __init__(self: pydrake.common.eigen_geometry.Quaternion, wxyz: numpy.ndarray[numpy.float64[4, 1]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.Quaternion, w: float, x: float, y: float, z: float) -> None

  4. __init__(self: pydrake.common.eigen_geometry.Quaternion, rotation: numpy.ndarray[numpy.float64[3, 3]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.Quaternion, other: pydrake.common.eigen_geometry.Quaternion) -> None

template cast

Instantiations: cast[float], cast[AutoDiffXd], cast[Expression]

cast[AutoDiffXd](self: pydrake.common.eigen_geometry.Quaternion) Eigen::Quaternion<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, 0>

Cast to desired scalar type.

cast[Expression](self: pydrake.common.eigen_geometry.Quaternion) Eigen::Quaternion<drake::symbolic::Expression, 0>

Cast to desired scalar type.

cast[float](self: pydrake.common.eigen_geometry.Quaternion) pydrake.common.eigen_geometry.Quaternion

Cast to desired scalar type.

conjugate(self: pydrake.common.eigen_geometry.Quaternion) pydrake.common.eigen_geometry.Quaternion
static Identity() pydrake.common.eigen_geometry.Quaternion
inverse(self: pydrake.common.eigen_geometry.Quaternion) pydrake.common.eigen_geometry.Quaternion
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion, arg0: pydrake.common.eigen_geometry.Quaternion) -> pydrake.common.eigen_geometry.Quaternion

Quaternion multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion, vector: numpy.ndarray[numpy.float64[3, 1]]) -> numpy.ndarray[numpy.float64[3, 1]]

Multiplication by a vector expressed in a frame

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion, vector: numpy.ndarray[numpy.float64[3, n]]) -> numpy.ndarray[numpy.float64[3, n]]

Multiplication by a list of vectors expressed in the same frame

rotation(self: pydrake.common.eigen_geometry.Quaternion) numpy.ndarray[numpy.float64[3, 3]]
set_rotation(self: pydrake.common.eigen_geometry.Quaternion, arg0: numpy.ndarray[numpy.float64[3, 3]]) None
set_wxyz(*args, **kwargs)

Overloaded function.

  1. set_wxyz(self: pydrake.common.eigen_geometry.Quaternion, wxyz: numpy.ndarray[numpy.float64[4, 1]]) -> None

  2. set_wxyz(self: pydrake.common.eigen_geometry.Quaternion, w: float, x: float, y: float, z: float) -> None

slerp(self: pydrake.common.eigen_geometry.Quaternion, t: float, other: pydrake.common.eigen_geometry.Quaternion) pydrake.common.eigen_geometry.Quaternion

The spherical linear interpolation between the two quaternions (self and other) at the parameter t in [0;1].

w(self: pydrake.common.eigen_geometry.Quaternion) float
wxyz(self: pydrake.common.eigen_geometry.Quaternion) numpy.ndarray[numpy.float64[4, 1]]
x(self: pydrake.common.eigen_geometry.Quaternion) float
xyz(self: pydrake.common.eigen_geometry.Quaternion) numpy.ndarray[numpy.float64[3, 1]]
y(self: pydrake.common.eigen_geometry.Quaternion) float
z(self: pydrake.common.eigen_geometry.Quaternion) float
template pydrake.common.eigen_geometry.Quaternion_

Instantiations: Quaternion_[float], Quaternion_[AutoDiffXd], Quaternion_[Expression]

class pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]

Provides a unit quaternion binding of Eigen::Quaternion<>.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) -> None

  2. __init__(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], wxyz: numpy.ndarray[object[4, 1]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], w: pydrake.autodiffutils.AutoDiffXd, x: pydrake.autodiffutils.AutoDiffXd, y: pydrake.autodiffutils.AutoDiffXd, z: pydrake.autodiffutils.AutoDiffXd) -> None

  4. __init__(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], rotation: numpy.ndarray[object[3, 3]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], other: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) -> None

template cast

Instantiations: cast[AutoDiffXd]

cast[AutoDiffXd](self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]

Cast to desired scalar type.

conjugate(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]
static Identity() pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]
inverse(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], arg0: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) -> pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]

Quaternion multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], vector: numpy.ndarray[object[3, 1]]) -> numpy.ndarray[object[3, 1]]

Multiplication by a vector expressed in a frame

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], vector: numpy.ndarray[object[3, n]]) -> numpy.ndarray[object[3, n]]

Multiplication by a list of vectors expressed in the same frame

rotation(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) numpy.ndarray[object[3, 3]]
set_rotation(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], arg0: numpy.ndarray[object[3, 3]]) None
set_wxyz(*args, **kwargs)

Overloaded function.

  1. set_wxyz(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], wxyz: numpy.ndarray[object[4, 1]]) -> None

  2. set_wxyz(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], w: pydrake.autodiffutils.AutoDiffXd, x: pydrake.autodiffutils.AutoDiffXd, y: pydrake.autodiffutils.AutoDiffXd, z: pydrake.autodiffutils.AutoDiffXd) -> None

slerp(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd], t: float, other: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]

The spherical linear interpolation between the two quaternions (self and other) at the parameter t in [0;1].

w(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
wxyz(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) numpy.ndarray[object[4, 1]]
x(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
xyz(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) numpy.ndarray[object[3, 1]]
y(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
z(self: pydrake.common.eigen_geometry.Quaternion_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
class pydrake.common.eigen_geometry.Quaternion_[Expression]

Provides a unit quaternion binding of Eigen::Quaternion<>.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) -> None

  2. __init__(self: pydrake.common.eigen_geometry.Quaternion_[Expression], wxyz: numpy.ndarray[object[4, 1]]) -> None

  3. __init__(self: pydrake.common.eigen_geometry.Quaternion_[Expression], w: pydrake.symbolic.Expression, x: pydrake.symbolic.Expression, y: pydrake.symbolic.Expression, z: pydrake.symbolic.Expression) -> None

  4. __init__(self: pydrake.common.eigen_geometry.Quaternion_[Expression], rotation: numpy.ndarray[object[3, 3]]) -> None

  5. __init__(self: pydrake.common.eigen_geometry.Quaternion_[Expression], other: pydrake.common.eigen_geometry.Quaternion_[Expression]) -> None

template cast

Instantiations: cast[Expression]

cast[Expression](self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.common.eigen_geometry.Quaternion_[Expression]

Cast to desired scalar type.

conjugate(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.common.eigen_geometry.Quaternion_[Expression]
static Identity() pydrake.common.eigen_geometry.Quaternion_[Expression]
inverse(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.common.eigen_geometry.Quaternion_[Expression]
multiply(*args, **kwargs)

Overloaded function.

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion_[Expression], arg0: pydrake.common.eigen_geometry.Quaternion_[Expression]) -> pydrake.common.eigen_geometry.Quaternion_[Expression]

Quaternion multiplication

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion_[Expression], vector: numpy.ndarray[object[3, 1]]) -> numpy.ndarray[object[3, 1]]

Multiplication by a vector expressed in a frame

  1. multiply(self: pydrake.common.eigen_geometry.Quaternion_[Expression], vector: numpy.ndarray[object[3, n]]) -> numpy.ndarray[object[3, n]]

Multiplication by a list of vectors expressed in the same frame

rotation(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) numpy.ndarray[object[3, 3]]
set_rotation(self: pydrake.common.eigen_geometry.Quaternion_[Expression], arg0: numpy.ndarray[object[3, 3]]) None
set_wxyz(*args, **kwargs)

Overloaded function.

  1. set_wxyz(self: pydrake.common.eigen_geometry.Quaternion_[Expression], wxyz: numpy.ndarray[object[4, 1]]) -> None

  2. set_wxyz(self: pydrake.common.eigen_geometry.Quaternion_[Expression], w: pydrake.symbolic.Expression, x: pydrake.symbolic.Expression, y: pydrake.symbolic.Expression, z: pydrake.symbolic.Expression) -> None

slerp(self: pydrake.common.eigen_geometry.Quaternion_[Expression], t: float, other: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.common.eigen_geometry.Quaternion_[Expression]

The spherical linear interpolation between the two quaternions (self and other) at the parameter t in [0;1].

w(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.symbolic.Expression
wxyz(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) numpy.ndarray[object[4, 1]]
x(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.symbolic.Expression
xyz(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) numpy.ndarray[object[3, 1]]
y(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.symbolic.Expression
z(self: pydrake.common.eigen_geometry.Quaternion_[Expression]) pydrake.symbolic.Expression