10 #ifndef EIGEN_ANGLEAXIS_H 11 #define EIGEN_ANGLEAXIS_H 48 template<
typename _Scalar>
55 using Base::operator*;
78 template<
typename Derived>
84 template<
typename QuatDerived>
87 template<
typename Derived>
105 {
return QuaternionType(*
this) * QuaternionType(other); }
109 {
return QuaternionType(*
this) *
other; }
113 {
return a * QuaternionType(b); }
119 template<
class QuatDerived>
121 template<
typename Derived>
124 template<
typename Derived>
133 template<
typename NewScalarType>
138 template<
typename OtherScalarType>
141 m_axis = other.
axis().template cast<Scalar>();
168 template<
typename Scalar>
169 template<
typename QuatDerived>
174 Scalar
n = q.
vec().norm();
176 n = q.
vec().stableNorm();
183 m_axis = q.
vec() /
n;
195 template<
typename Scalar>
196 template<
typename Derived>
201 return *
this = QuaternionType(mat);
207 template<
typename Scalar>
208 template<
typename Derived>
211 return *
this = QuaternionType(mat);
216 template<
typename Scalar>
223 Vector3 sin_axis =
sin(m_angle) * m_axis;
224 Scalar
c =
cos(m_angle);
225 Vector3 cos1_axis = (
Scalar(1)-
c) * m_axis;
228 tmp = cos1_axis.x() * m_axis.y();
229 res.
coeffRef(0,1) = tmp - sin_axis.z();
230 res.
coeffRef(1,0) = tmp + sin_axis.z();
232 tmp = cos1_axis.x() * m_axis.z();
233 res.
coeffRef(0,2) = tmp + sin_axis.y();
234 res.
coeffRef(2,0) = tmp - sin_axis.y();
236 tmp = cos1_axis.y() * m_axis.z();
237 res.
coeffRef(1,2) = tmp - sin_axis.x();
238 res.
coeffRef(2,1) = tmp + sin_axis.x();
240 res.diagonal() = (cos1_axis.cwiseProduct(m_axis)).
array() +
c;
247 #endif // EIGEN_ANGLEAXIS_H
Jet< T, N > cos(const Jet< T, N > &f)
EIGEN_DEVICE_FUNC AngleAxis(const MatrixBase< Derived > &m)
EIGEN_DEVICE_FUNC AngleAxis(const Scalar &angle, const MatrixBase< Derived > &axis)
static EIGEN_DEVICE_FUNC const AngleAxis Identity()
EIGEN_DEVICE_FUNC AngleAxis & operator=(const QuaternionBase< QuatDerived > &q)
EIGEN_DEVICE_FUNC const VectorBlock< const Coefficients, 3 > vec() const
Matrix< Scalar, 3, 3 > Matrix3
EIGEN_DEVICE_FUNC internal::cast_return_type< AngleAxis, AngleAxis< NewScalarType > >::type cast() const
Jet< T, N > sin(const Jet< T, N > &f)
Namespace containing all symbols from the Eigen library.
EIGEN_DEVICE_FUNC CoeffReturnType w() const
AngleAxis< double > AngleAxisd
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
EIGEN_DEVICE_FUNC AngleAxis()
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
static EIGEN_DEVICE_FUNC Matrix< Scalar, 2, 2 > toRotationMatrix(const Scalar &s)
EIGEN_DEVICE_FUNC Scalar angle() const
AngleAxis< float > AngleAxisf
Common base class for compact rotation representations.
EIGEN_DEVICE_FUNC const Scalar & q
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorUInt128< uint64_t, uint64_t > operator*(const TensorUInt128< HL, LL > &lhs, const TensorUInt128< HR, LR > &rhs)
Base class for quaternion expressions.
Matrix< Scalar, 3, 1 > Vector3
EIGEN_DEVICE_FUNC const Vector3 & axis() const
#define EIGEN_DEVICE_FUNC
EIGEN_DEVICE_FUNC AngleAxis & fromRotationMatrix(const MatrixBase< Derived > &m)
EIGEN_DEVICE_FUNC AngleAxis inverse() const
The quaternion class used to represent 3D orientations and rotations.
#define EIGEN_USING_STD(FUNC)
Quaternion< Scalar > QuaternionType
EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix(void) const
EIGEN_DEVICE_FUNC Vector3 & axis()
const AutoDiffScalar< Matrix< typename internal::traits< typename internal::remove_all< DerTypeA >::type >::Scalar, Dynamic, 1 > > atan2(const AutoDiffScalar< DerTypeA > &a, const AutoDiffScalar< DerTypeB > &b)
EIGEN_DEVICE_FUNC Scalar & angle()
The matrix class, also used for vectors and row-vectors.
EIGEN_DEVICE_FUNC bool isApprox(const Scalar &x, const Scalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
EIGEN_DEVICE_FUNC AngleAxis(const QuaternionBase< QuatDerived > &q)
Base class for all dense matrices, vectors, and expressions.
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
EIGEN_DEVICE_FUNC AngleAxis(const AngleAxis< OtherScalarType > &other)
EIGEN_DEVICE_FUNC bool isApprox(const AngleAxis &other, const typename NumTraits< Scalar >::Real &prec=NumTraits< Scalar >::dummy_precision()) const
RotationBase< AngleAxis< _Scalar >, 3 > Base