Drake
|
THIS FILE IS DEPRECATED. More...
#include <Eigen/Dense>
#include <cstring>
#include <cmath>
#include <random>
#include "drake/common/constants.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/eigen_types.h"
#include "drake/drakeGeometryUtil_export.h"
#include "drake/math/gradient.h"
#include "drake/math/quaternion.h"
#include "drake/util/drakeGradientUtil.h"
Go to the source code of this file.
Classes | |
struct | TransformSpatial< Derived > |
struct | DHomogTrans< DerivedQdotToV > |
Functions | |
DRAKEGEOMETRYUTIL_EXPORT double | angleDiff (double phi1, double phi2) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Vector4d | uniformlyRandomAxisAngle (std::default_random_engine &generator) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Vector4d | uniformlyRandomQuat (std::default_random_engine &generator) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Matrix3d | uniformlyRandomRotmat (std::default_random_engine &generator) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Vector3d | uniformlyRandomRPY (std::default_random_engine &generator) |
template<typename Derived > | |
void | normalizeVec (const Eigen::MatrixBase< Derived > &x, typename Derived::PlainObject &x_norm, typename drake::math::Gradient< Derived, Derived::RowsAtCompileTime, 1 >::type *dx_norm=nullptr, typename drake::math::Gradient< Derived, Derived::RowsAtCompileTime, 2 >::type *ddx_norm=nullptr) |
DRAKEGEOMETRYUTIL_EXPORT int | rotationRepresentationSize (int rotation_type) |
template<typename Derived > | |
drake::math::Gradient< Eigen::Matrix< typename Derived::Scalar, 3, 3 >, drake::kQuaternionSize >::type | dquat2rotmat (const Eigen::MatrixBase< Derived > &q) |
template<typename DerivedR , typename DerivedDR > | |
drake::math::Gradient< Eigen::Matrix< typename DerivedR::Scalar, drake::kRpySize, 1 >, DerivedDR::ColsAtCompileTime >::type | drotmat2rpy (const Eigen::MatrixBase< DerivedR > &R, const Eigen::MatrixBase< DerivedDR > &dR) |
template<typename DerivedR , typename DerivedDR > | |
drake::math::Gradient< Eigen::Matrix< typename DerivedR::Scalar, drake::kQuaternionSize, 1 >, DerivedDR::ColsAtCompileTime >::type | drotmat2quat (const Eigen::MatrixBase< DerivedR > &R, const Eigen::MatrixBase< DerivedDR > &dR) |
template<typename Derived > | |
Eigen::Matrix< typename Derived::Scalar, 3, 3 > | vectorToSkewSymmetric (const Eigen::MatrixBase< Derived > &p) |
template<typename DerivedA , typename DerivedB > | |
Eigen::Matrix< typename DerivedA::Scalar, 3, Eigen::Dynamic > | dcrossProduct (const Eigen::MatrixBase< DerivedA > &a, const Eigen::MatrixBase< DerivedB > &b, const typename drake::math::Gradient< DerivedA, Eigen::Dynamic >::type &da, const typename drake::math::Gradient< DerivedB, Eigen::Dynamic >::type &db) |
template<typename DerivedQ , typename DerivedM , typename DerivedDM > | |
void | angularvel2quatdotMatrix (const Eigen::MatrixBase< DerivedQ > &q, Eigen::MatrixBase< DerivedM > &M, Eigen::MatrixBase< DerivedDM > *dM=nullptr) |
template<typename DerivedRPY , typename DerivedPhi , typename DerivedDPhi , typename DerivedDDPhi > | |
void | angularvel2rpydotMatrix (const Eigen::MatrixBase< DerivedRPY > &rpy, typename Eigen::MatrixBase< DerivedPhi > &phi, typename Eigen::MatrixBase< DerivedDPhi > *dphi=nullptr, typename Eigen::MatrixBase< DerivedDDPhi > *ddphi=nullptr) |
template<typename DerivedRPY , typename DerivedE > | |
void | rpydot2angularvelMatrix (const Eigen::MatrixBase< DerivedRPY > &rpy, Eigen::MatrixBase< DerivedE > &E, typename drake::math::Gradient< DerivedE, drake::kRpySize, 1 >::type *dE=nullptr) |
template<typename Derived > | |
Eigen::Matrix< typename Derived::Scalar, 3, 4 > | quatdot2angularvelMatrix (const Eigen::MatrixBase< Derived > &q) |
template<typename DerivedRPY , typename DerivedRPYdot , typename DerivedOMEGA > | |
void | rpydot2angularvel (const Eigen::MatrixBase< DerivedRPY > &rpy, const Eigen::MatrixBase< DerivedRPYdot > &rpydot, Eigen::MatrixBase< DerivedOMEGA > &omega, typename drake::math::Gradient< DerivedOMEGA, drake::kRpySize, 1 >::type *domega=nullptr) |
template<typename DerivedM > | |
TransformSpatial< DerivedM >::type | transformSpatialMotion (const Eigen::Transform< typename DerivedM::Scalar, 3, Eigen::Isometry > &T, const Eigen::MatrixBase< DerivedM > &M) |
template<typename Scalar , typename DerivedX , typename DerivedDT , typename DerivedDX > | |
drake::math::Gradient< DerivedX, DerivedDX::ColsAtCompileTime, 1 >::type | dTransformSpatialMotion (const Eigen::Transform< Scalar, 3, Eigen::Isometry > &T, const Eigen::MatrixBase< DerivedX > &X, const Eigen::MatrixBase< DerivedDT > &dT, const Eigen::MatrixBase< DerivedDX > &dX) |
template<typename DerivedF > | |
TransformSpatial< DerivedF >::type | transformSpatialForce (const Eigen::Transform< typename DerivedF::Scalar, 3, Eigen::Isometry > &T, const Eigen::MatrixBase< DerivedF > &F) |
template<typename Scalar , typename DerivedX , typename DerivedDT , typename DerivedDX > | |
drake::math::Gradient< DerivedX, DerivedDX::ColsAtCompileTime >::type | dTransformSpatialForce (const Eigen::Transform< Scalar, 3, Eigen::Isometry > &T, const Eigen::MatrixBase< DerivedX > &X, const Eigen::MatrixBase< DerivedDT > &dT, const Eigen::MatrixBase< DerivedDX > &dX) |
template<typename DerivedI > | |
bool | isRegularInertiaMatrix (const Eigen::MatrixBase< DerivedI > &I) |
template<typename DerivedI > | |
drake::SquareTwistMatrix< typename DerivedI::Scalar > | transformSpatialInertia (const Eigen::Transform< typename DerivedI::Scalar, drake::kSpaceDimension, Eigen::Isometry > &T_current_to_new, const Eigen::MatrixBase< DerivedI > &I) |
template<typename DerivedA , typename DerivedB > | |
TransformSpatial< DerivedB >::type | crossSpatialMotion (const Eigen::MatrixBase< DerivedA > &a, const Eigen::MatrixBase< DerivedB > &b) |
template<typename DerivedA , typename DerivedB > | |
TransformSpatial< DerivedB >::type | crossSpatialForce (const Eigen::MatrixBase< DerivedA > &a, const Eigen::MatrixBase< DerivedB > &b) |
template<typename DerivedA , typename DerivedB > | |
drake::TwistMatrix< typename DerivedA::Scalar > | dCrossSpatialMotion (const Eigen::MatrixBase< DerivedA > &a, const Eigen::MatrixBase< DerivedB > &b, const typename drake::math::Gradient< DerivedA, Eigen::Dynamic >::type &da, const typename drake::math::Gradient< DerivedB, Eigen::Dynamic >::type &db) |
template<typename DerivedA , typename DerivedB > | |
drake::TwistMatrix< typename DerivedA::Scalar > | dCrossSpatialForce (const Eigen::MatrixBase< DerivedA > &a, const Eigen::MatrixBase< DerivedB > &b, const typename drake::math::Gradient< DerivedA, Eigen::Dynamic >::type &da, const typename drake::math::Gradient< DerivedB, Eigen::Dynamic >::type &db) |
template<typename DerivedS , typename DerivedQdotToV > | |
DHomogTrans< DerivedQdotToV >::type | dHomogTrans (const Eigen::Transform< typename DerivedQdotToV::Scalar, 3, Eigen::Isometry > &T, const Eigen::MatrixBase< DerivedS > &S, const Eigen::MatrixBase< DerivedQdotToV > &qdot_to_v) |
template<typename DerivedDT > | |
DHomogTrans< DerivedDT >::type | dHomogTransInv (const Eigen::Transform< typename DerivedDT::Scalar, 3, Eigen::Isometry > &T, const Eigen::MatrixBase< DerivedDT > &dT) |
template<typename Derived > | |
Eigen::Matrix< typename Derived::Scalar, 3, 1 > | flipExpmap (const Eigen::MatrixBase< Derived > &expmap) |
template<typename Derived1 , typename Derived2 > | |
Eigen::Matrix< typename Derived1::Scalar, 3, 1 > | unwrapExpmap (const Eigen::MatrixBase< Derived1 > &expmap1, const Eigen::MatrixBase< Derived2 > &expmap2) |
Variables | |
const int | HOMOGENEOUS_TRANSFORM_SIZE = 16 |
const int | QUAT_SIZE = 4 |
const int | RPY_SIZE = 3 |
const int | SPACE_DIMENSION = 3 |
const int | RotmatSize = drake::kSpaceDimension * drake::kSpaceDimension |
THIS FILE IS DEPRECATED.
Its contents are moving into drake/math.
void angularvel2quatdotMatrix | ( | const Eigen::MatrixBase< DerivedQ > & | q, |
Eigen::MatrixBase< DerivedM > & | M, | ||
Eigen::MatrixBase< DerivedDM > * | dM = nullptr |
||
) |
void angularvel2rpydotMatrix | ( | const Eigen::MatrixBase< DerivedRPY > & | rpy, |
typename Eigen::MatrixBase< DerivedPhi > & | phi, | ||
typename Eigen::MatrixBase< DerivedDPhi > * | dphi = nullptr , |
||
typename Eigen::MatrixBase< DerivedDDPhi > * | ddphi = nullptr |
||
) |
TransformSpatial<DerivedB>::type crossSpatialForce | ( | const Eigen::MatrixBase< DerivedA > & | a, |
const Eigen::MatrixBase< DerivedB > & | b | ||
) |
TransformSpatial<DerivedB>::type crossSpatialMotion | ( | const Eigen::MatrixBase< DerivedA > & | a, |
const Eigen::MatrixBase< DerivedB > & | b | ||
) |
Eigen::Matrix<typename DerivedA::Scalar, 3, Eigen::Dynamic> dcrossProduct | ( | const Eigen::MatrixBase< DerivedA > & | a, |
const Eigen::MatrixBase< DerivedB > & | b, | ||
const typename drake::math::Gradient< DerivedA, Eigen::Dynamic >::type & | da, | ||
const typename drake::math::Gradient< DerivedB, Eigen::Dynamic >::type & | db | ||
) |
drake::TwistMatrix<typename DerivedA::Scalar> dCrossSpatialForce | ( | const Eigen::MatrixBase< DerivedA > & | a, |
const Eigen::MatrixBase< DerivedB > & | b, | ||
const typename drake::math::Gradient< DerivedA, Eigen::Dynamic >::type & | da, | ||
const typename drake::math::Gradient< DerivedB, Eigen::Dynamic >::type & | db | ||
) |
drake::TwistMatrix<typename DerivedA::Scalar> dCrossSpatialMotion | ( | const Eigen::MatrixBase< DerivedA > & | a, |
const Eigen::MatrixBase< DerivedB > & | b, | ||
const typename drake::math::Gradient< DerivedA, Eigen::Dynamic >::type & | da, | ||
const typename drake::math::Gradient< DerivedB, Eigen::Dynamic >::type & | db | ||
) |
DHomogTrans<DerivedQdotToV>::type dHomogTrans | ( | const Eigen::Transform< typename DerivedQdotToV::Scalar, 3, Eigen::Isometry > & | T, |
const Eigen::MatrixBase< DerivedS > & | S, | ||
const Eigen::MatrixBase< DerivedQdotToV > & | qdot_to_v | ||
) |
DHomogTrans<DerivedDT>::type dHomogTransInv | ( | const Eigen::Transform< typename DerivedDT::Scalar, 3, Eigen::Isometry > & | T, |
const Eigen::MatrixBase< DerivedDT > & | dT | ||
) |
drake::math::Gradient<Eigen::Matrix<typename Derived::Scalar, 3, 3>, drake::kQuaternionSize>::type dquat2rotmat | ( | const Eigen::MatrixBase< Derived > & | q | ) |
drake::math::Gradient< Eigen::Matrix<typename DerivedR::Scalar, drake::kQuaternionSize, 1>, DerivedDR::ColsAtCompileTime>::type drotmat2quat | ( | const Eigen::MatrixBase< DerivedR > & | R, |
const Eigen::MatrixBase< DerivedDR > & | dR | ||
) |
drake::math::Gradient< Eigen::Matrix<typename DerivedR::Scalar, drake::kRpySize, 1>, DerivedDR::ColsAtCompileTime>::type drotmat2rpy | ( | const Eigen::MatrixBase< DerivedR > & | R, |
const Eigen::MatrixBase< DerivedDR > & | dR | ||
) |
drake::math::Gradient<DerivedX, DerivedDX::ColsAtCompileTime>::type dTransformSpatialForce | ( | const Eigen::Transform< Scalar, 3, Eigen::Isometry > & | T, |
const Eigen::MatrixBase< DerivedX > & | X, | ||
const Eigen::MatrixBase< DerivedDT > & | dT, | ||
const Eigen::MatrixBase< DerivedDX > & | dX | ||
) |
drake::math::Gradient<DerivedX, DerivedDX::ColsAtCompileTime, 1>::type dTransformSpatialMotion | ( | const Eigen::Transform< Scalar, 3, Eigen::Isometry > & | T, |
const Eigen::MatrixBase< DerivedX > & | X, | ||
const Eigen::MatrixBase< DerivedDT > & | dT, | ||
const Eigen::MatrixBase< DerivedDX > & | dX | ||
) |
Eigen::Matrix<typename Derived::Scalar, 3, 1> flipExpmap | ( | const Eigen::MatrixBase< Derived > & | expmap | ) |
bool isRegularInertiaMatrix | ( | const Eigen::MatrixBase< DerivedI > & | I | ) |
void normalizeVec | ( | const Eigen::MatrixBase< Derived > & | x, |
typename Derived::PlainObject & | x_norm, | ||
typename drake::math::Gradient< Derived, Derived::RowsAtCompileTime, 1 >::type * | dx_norm = nullptr , |
||
typename drake::math::Gradient< Derived, Derived::RowsAtCompileTime, 2 >::type * | ddx_norm = nullptr |
||
) |
Eigen::Matrix<typename Derived::Scalar, 3, 4> quatdot2angularvelMatrix | ( | const Eigen::MatrixBase< Derived > & | q | ) |
DRAKEGEOMETRYUTIL_EXPORT int rotationRepresentationSize | ( | int | rotation_type | ) |
void rpydot2angularvel | ( | const Eigen::MatrixBase< DerivedRPY > & | rpy, |
const Eigen::MatrixBase< DerivedRPYdot > & | rpydot, | ||
Eigen::MatrixBase< DerivedOMEGA > & | omega, | ||
typename drake::math::Gradient< DerivedOMEGA, drake::kRpySize, 1 >::type * | domega = nullptr |
||
) |
void rpydot2angularvelMatrix | ( | const Eigen::MatrixBase< DerivedRPY > & | rpy, |
Eigen::MatrixBase< DerivedE > & | E, | ||
typename drake::math::Gradient< DerivedE, drake::kRpySize, 1 >::type * | dE = nullptr |
||
) |
TransformSpatial<DerivedF>::type transformSpatialForce | ( | const Eigen::Transform< typename DerivedF::Scalar, 3, Eigen::Isometry > & | T, |
const Eigen::MatrixBase< DerivedF > & | F | ||
) |
drake::SquareTwistMatrix<typename DerivedI::Scalar> transformSpatialInertia | ( | const Eigen::Transform< typename DerivedI::Scalar, drake::kSpaceDimension, Eigen::Isometry > & | T_current_to_new, |
const Eigen::MatrixBase< DerivedI > & | I | ||
) |
TransformSpatial<DerivedM>::type transformSpatialMotion | ( | const Eigen::Transform< typename DerivedM::Scalar, 3, Eigen::Isometry > & | T, |
const Eigen::MatrixBase< DerivedM > & | M | ||
) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Vector4d uniformlyRandomAxisAngle | ( | std::default_random_engine & | generator | ) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Vector4d uniformlyRandomQuat | ( | std::default_random_engine & | generator | ) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Matrix3d uniformlyRandomRotmat | ( | std::default_random_engine & | generator | ) |
DRAKEGEOMETRYUTIL_EXPORT Eigen::Vector3d uniformlyRandomRPY | ( | std::default_random_engine & | generator | ) |
Eigen::Matrix<typename Derived1::Scalar, 3, 1> unwrapExpmap | ( | const Eigen::MatrixBase< Derived1 > & | expmap1, |
const Eigen::MatrixBase< Derived2 > & | expmap2 | ||
) |
Eigen::Matrix<typename Derived::Scalar, 3, 3> vectorToSkewSymmetric | ( | const Eigen::MatrixBase< Derived > & | p | ) |
const int HOMOGENEOUS_TRANSFORM_SIZE = 16 |
const int QUAT_SIZE = 4 |
const int RotmatSize = drake::kSpaceDimension * drake::kSpaceDimension |
const int RPY_SIZE = 3 |
const int SPACE_DIMENSION = 3 |