Drake
|
Namespaces | |
internal | |
Classes | |
struct | AutoDiffToGradientMatrix |
struct | AutoDiffToValueMatrix |
struct | Gradient |
struct | Gradient< Derived, Nq, 1 > |
Functions | |
template<typename Derived > | |
AutoDiffToValueMatrix< Derived >::type | autoDiffToValueMatrix (const Eigen::MatrixBase< Derived > &auto_diff_matrix) |
template<typename Derived > | |
AutoDiffToGradientMatrix< Derived >::type | autoDiffToGradientMatrix (const Eigen::MatrixBase< Derived > &auto_diff_matrix, int num_variables=Eigen::Dynamic) |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | axis2quat (const Eigen::MatrixBase< Derived > &a) |
template<typename Derived > | |
Matrix3< typename Derived::Scalar > | axis2rotmat (const Eigen::MatrixBase< Derived > &a) |
template<typename Derived > | |
Vector3< typename Derived::Scalar > | axis2rpy (const Eigen::MatrixBase< Derived > &a) |
template<typename Scalar > | |
void | cylindrical2cartesian (const Vector3< Scalar > &m_cylinder_axis, const Vector3< Scalar > &m_cylinder_x_dir, const Vector3< Scalar > &cylinder_origin, const Vector6< Scalar > &x_cylinder, const Vector6< Scalar > &v_cylinder, Vector6< Scalar > &x_cartesian, Vector6< Scalar > &v_cartesian, Matrix6< Scalar > &J, Vector6< Scalar > &Jdotv) |
template<typename Scalar > | |
void | cartesian2cylindrical (const Vector3< Scalar > &m_cylinder_axis, const Vector3< Scalar > &m_cylinder_x_dir, const Vector3< Scalar > &cylinder_origin, const Vector6< Scalar > &x_cartesian, const Vector6< Scalar > &v_cartesian, Vector6< Scalar > &x_cylinder, Vector6< Scalar > &v_cylinder, Matrix6< Scalar > &J, Vector6< Scalar > &Jdotv) |
template<typename Derived > | |
Eigen::Matrix< typename Derived::Scalar, 4, 1 > | expmap2quat (const Eigen::MatrixBase< Derived > &v) |
template<typename DerivedQ > | |
Eigen::Matrix< typename DerivedQ::Scalar, 3, 1 > | quat2expmap (const Eigen::MatrixBase< DerivedQ > &q) |
template<typename Derived1 , typename Derived2 > | |
Eigen::Matrix< typename Derived1::Scalar, 3, 1 > | closestExpmap (const Eigen::MatrixBase< Derived1 > &expmap1, const Eigen::MatrixBase< Derived2 > &expmap2) |
template<typename DerivedQ , typename DerivedE > | |
void | quat2expmapSequence (const Eigen::MatrixBase< DerivedQ > &quat, const Eigen::MatrixBase< DerivedQ > &quat_dot, Eigen::MatrixBase< DerivedE > &expmap, Eigen::MatrixBase< DerivedE > &expmap_dot) |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | quatConjugate (const Eigen::MatrixBase< Derived > &q) |
template<typename Derived1 , typename Derived2 > | |
Vector4< typename Derived1::Scalar > | quatProduct (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2) |
template<typename DerivedQ , typename DerivedV > | |
Vector3< typename DerivedV::Scalar > | quatRotateVec (const Eigen::MatrixBase< DerivedQ > &q, const Eigen::MatrixBase< DerivedV > &v) |
template<typename Derived1 , typename Derived2 > | |
Vector4< typename Derived1::Scalar > | quatDiff (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2) |
template<typename Derived1 , typename Derived2 , typename DerivedU > | |
Derived1::Scalar | quatDiffAxisInvar (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2, const Eigen::MatrixBase< DerivedU > &u) |
template<typename Derived > | |
Derived::Scalar | quatNorm (const Eigen::MatrixBase< Derived > &q) |
template<typename Derived1 , typename Derived2 , typename Scalar > | |
Vector4< Scalar > | Slerp (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2, const Scalar &interpolation_parameter) |
Q = Slerp(q1, q2, f) Spherical linear interpolation between two quaternions This function uses the implementation given in Algorithm 8 of [1]. More... | |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | quat2axis (const Eigen::MatrixBase< Derived > &q) |
template<typename Derived > | |
Matrix3< typename Derived::Scalar > | quat2rotmat (const Eigen::MatrixBase< Derived > &q) |
template<typename Derived > | |
Vector3< typename Derived::Scalar > | quat2rpy (const Eigen::MatrixBase< Derived > &q) |
template<typename Derived > | |
Eigen::Quaternion< typename Derived::Scalar > | quat2eigenQuaternion (const Eigen::MatrixBase< Derived > &q) |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | rpy2quat (const Eigen::MatrixBase< Derived > &rpy) |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | rpy2axis (const Eigen::MatrixBase< Derived > &rpy) |
template<typename Derived > | |
Matrix3< typename Derived::Scalar > | rpy2rotmat (const Eigen::MatrixBase< Derived > &rpy) |
template<typename Derived > | |
Eigen::Matrix< typename Derived::Scalar, 9, 3 > | drpy2rotmat (const Eigen::MatrixBase< Derived > &rpy) |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | rotmat2axis (const Eigen::MatrixBase< Derived > &R) |
template<typename Derived > | |
Vector4< typename Derived::Scalar > | rotmat2quat (const Eigen::MatrixBase< Derived > &M) |
template<typename Derived > | |
Vector3< typename Derived::Scalar > | rotmat2rpy (const Eigen::MatrixBase< Derived > &R) |
template<typename Derived > | |
VectorX< typename Derived::Scalar > | rotmat2Representation (const Eigen::MatrixBase< Derived > &R, int rotation_type) |
AutoDiffToGradientMatrix<Derived>::type drake::math::autoDiffToGradientMatrix | ( | const Eigen::MatrixBase< Derived > & | auto_diff_matrix, |
int | num_variables = Eigen::Dynamic |
||
) |
AutoDiffToValueMatrix<Derived>::type drake::math::autoDiffToValueMatrix | ( | const Eigen::MatrixBase< Derived > & | auto_diff_matrix | ) |
Vector4<typename Derived::Scalar> drake::math::axis2quat | ( | const Eigen::MatrixBase< Derived > & | a | ) |
Matrix3<typename Derived::Scalar> drake::math::axis2rotmat | ( | const Eigen::MatrixBase< Derived > & | a | ) |
Vector3<typename Derived::Scalar> drake::math::axis2rpy | ( | const Eigen::MatrixBase< Derived > & | a | ) |
void drake::math::cartesian2cylindrical | ( | const Vector3< Scalar > & | m_cylinder_axis, |
const Vector3< Scalar > & | m_cylinder_x_dir, | ||
const Vector3< Scalar > & | cylinder_origin, | ||
const Vector6< Scalar > & | x_cartesian, | ||
const Vector6< Scalar > & | v_cartesian, | ||
Vector6< Scalar > & | x_cylinder, | ||
Vector6< Scalar > & | v_cylinder, | ||
Matrix6< Scalar > & | J, | ||
Vector6< Scalar > & | Jdotv | ||
) |
Eigen::Matrix<typename Derived1::Scalar, 3, 1> drake::math::closestExpmap | ( | const Eigen::MatrixBase< Derived1 > & | expmap1, |
const Eigen::MatrixBase< Derived2 > & | expmap2 | ||
) |
void drake::math::cylindrical2cartesian | ( | const Vector3< Scalar > & | m_cylinder_axis, |
const Vector3< Scalar > & | m_cylinder_x_dir, | ||
const Vector3< Scalar > & | cylinder_origin, | ||
const Vector6< Scalar > & | x_cylinder, | ||
const Vector6< Scalar > & | v_cylinder, | ||
Vector6< Scalar > & | x_cartesian, | ||
Vector6< Scalar > & | v_cartesian, | ||
Matrix6< Scalar > & | J, | ||
Vector6< Scalar > & | Jdotv | ||
) |
Eigen::Matrix<typename Derived::Scalar, 9, 3> drake::math::drpy2rotmat | ( | const Eigen::MatrixBase< Derived > & | rpy | ) |
Eigen::Matrix<typename Derived::Scalar, 4, 1> drake::math::expmap2quat | ( | const Eigen::MatrixBase< Derived > & | v | ) |
Vector4<typename Derived::Scalar> drake::math::quat2axis | ( | const Eigen::MatrixBase< Derived > & | q | ) |
Eigen::Quaternion<typename Derived::Scalar> drake::math::quat2eigenQuaternion | ( | const Eigen::MatrixBase< Derived > & | q | ) |
Eigen::Matrix<typename DerivedQ::Scalar, 3, 1> drake::math::quat2expmap | ( | const Eigen::MatrixBase< DerivedQ > & | q | ) |
void drake::math::quat2expmapSequence | ( | const Eigen::MatrixBase< DerivedQ > & | quat, |
const Eigen::MatrixBase< DerivedQ > & | quat_dot, | ||
Eigen::MatrixBase< DerivedE > & | expmap, | ||
Eigen::MatrixBase< DerivedE > & | expmap_dot | ||
) |
Matrix3<typename Derived::Scalar> drake::math::quat2rotmat | ( | const Eigen::MatrixBase< Derived > & | q | ) |
Vector3<typename Derived::Scalar> drake::math::quat2rpy | ( | const Eigen::MatrixBase< Derived > & | q | ) |
Vector4<typename Derived::Scalar> drake::math::quatConjugate | ( | const Eigen::MatrixBase< Derived > & | q | ) |
Vector4<typename Derived1::Scalar> drake::math::quatDiff | ( | const Eigen::MatrixBase< Derived1 > & | q1, |
const Eigen::MatrixBase< Derived2 > & | q2 | ||
) |
Derived1::Scalar drake::math::quatDiffAxisInvar | ( | const Eigen::MatrixBase< Derived1 > & | q1, |
const Eigen::MatrixBase< Derived2 > & | q2, | ||
const Eigen::MatrixBase< DerivedU > & | u | ||
) |
Derived::Scalar drake::math::quatNorm | ( | const Eigen::MatrixBase< Derived > & | q | ) |
Vector4<typename Derived1::Scalar> drake::math::quatProduct | ( | const Eigen::MatrixBase< Derived1 > & | q1, |
const Eigen::MatrixBase< Derived2 > & | q2 | ||
) |
Vector3<typename DerivedV::Scalar> drake::math::quatRotateVec | ( | const Eigen::MatrixBase< DerivedQ > & | q, |
const Eigen::MatrixBase< DerivedV > & | v | ||
) |
Vector4<typename Derived::Scalar> drake::math::rotmat2axis | ( | const Eigen::MatrixBase< Derived > & | R | ) |
Vector4<typename Derived::Scalar> drake::math::rotmat2quat | ( | const Eigen::MatrixBase< Derived > & | M | ) |
VectorX<typename Derived::Scalar> drake::math::rotmat2Representation | ( | const Eigen::MatrixBase< Derived > & | R, |
int | rotation_type | ||
) |
Vector3<typename Derived::Scalar> drake::math::rotmat2rpy | ( | const Eigen::MatrixBase< Derived > & | R | ) |
Vector4<typename Derived::Scalar> drake::math::rpy2axis | ( | const Eigen::MatrixBase< Derived > & | rpy | ) |
Vector4<typename Derived::Scalar> drake::math::rpy2quat | ( | const Eigen::MatrixBase< Derived > & | rpy | ) |
Matrix3<typename Derived::Scalar> drake::math::rpy2rotmat | ( | const Eigen::MatrixBase< Derived > & | rpy | ) |
Vector4<Scalar> drake::math::Slerp | ( | const Eigen::MatrixBase< Derived1 > & | q1, |
const Eigen::MatrixBase< Derived2 > & | q2, | ||
const Scalar & | interpolation_parameter | ||
) |
Q = Slerp(q1, q2, f) Spherical linear interpolation between two quaternions This function uses the implementation given in Algorithm 8 of [1].
q1 | Initial quaternion (w, x, y, z) |
q2 | Final quaternion (w, x, y, z) |
interpolation_parameter | between 0 and 1 (inclusive) |
Q | Interpolated quaternion(s). 4-by-1 vector. |
[1] Kuffner, J.J., "Effective sampling and distance metrics for 3D rigid body path planning," Robotics and Automation, 2004. Proceedings. ICRA '04. 2004 IEEE International Conference on , vol.4, no., pp.3993, 3998 Vol.4, April 26-May 1, 2004 doi: 10.1109/ROBOT.2004.1308895