Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
Eigen::Map< Sophus::SO3< Scalar_ >, Options > Class Template Reference

#include <so3.hpp>

Inheritance diagram for Eigen::Map< Sophus::SO3< Scalar_ >, Options >:
Inheritance graph
[legend]

Public Types

using Adjoint = typename Base::Adjoint
 
using Base = Sophus::SO3Base< Map< Sophus::SO3< Scalar_ >, Options > >
 
using HomogeneousPoint = typename Base::HomogeneousPoint
 
using Point = typename Base::Point
 
using Scalar = Scalar_
 
using Tangent = typename Base::Tangent
 
using Transformation = typename Base::Transformation
 
- Public Types inherited from Sophus::SO3Base< Derived >
using Adjoint = Matrix< Scalar, DoF, DoF >
 
using HomogeneousPoint = Vector4< Scalar >
 
template<typename HPointDerived >
using HomogeneousPointProduct = Vector4< ReturnScalar< HPointDerived > >
 
using Line = ParametrizedLine3< Scalar >
 
using Point = Vector3< Scalar >
 
template<typename PointDerived >
using PointProduct = Vector3< ReturnScalar< PointDerived > >
 
using QuaternionType = typename Eigen::internal::traits< Derived >::QuaternionType
 
template<typename OtherDerived >
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType
 
using Scalar = typename Eigen::internal::traits< Derived >::Scalar
 
template<typename OtherDerived >
using SO3Product = SO3< ReturnScalar< OtherDerived > >
 
using Tangent = Vector< Scalar, DoF >
 
using Transformation = Matrix< Scalar, N, N >
 

Public Member Functions

 EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR (Map)
 
SOPHUS_FUNC Map (Scalar *coeffs)
 
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 4>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
 Group action on homogeneous 3-points. See above for more details. More...
 
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 3>::value>::type>
SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const
 
SOPHUS_FUNC Line operator* (Line const &l) const
 
template<typename OtherDerived >
SOPHUS_FUNC SO3Product< OtherDerived > operator* (SO3Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SO3Base< Derived > & operator*= (SO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC Map< Eigen::Quaternion< Scalar >, Options > const & unit_quaternion () const
 
- Public Member Functions inherited from Sophus::SO3Base< Derived >
SOPHUS_FUNC Adjoint Adj () const
 Adjoint transformation. More...
 
template<class S = Scalar>
SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > angleX () const
 
template<class S = Scalar>
SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > angleY () const
 
template<class S = Scalar>
SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > angleZ () const
 
template<class NewScalarType >
SOPHUS_FUNC SO3< NewScalarType > cast () const
 
SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoFDx_this_mul_exp_x_at_0 () const
 
SOPHUS_FUNC SO3< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC TangentAndTheta logAndTheta () const
 
SOPHUS_FUNC Transformation matrix () const
 
SOPHUS_FUNC void normalize ()
 
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 4>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
 Group action on homogeneous 3-points. See above for more details. More...
 
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 3>::value>::type>
SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const
 
SOPHUS_FUNC Line operator* (Line const &l) const
 
template<typename OtherDerived >
SOPHUS_FUNC SO3Product< OtherDerived > operator* (SO3Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SO3Base< Derived > & operator*= (SO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC SO3Baseoperator= (SO3Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SO3Base< Derived > & operator= (SO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quaternion)
 
SOPHUS_FUNC QuaternionType const & unit_quaternion () const
 

Protected Member Functions

SOPHUS_FUNC Map< Eigen::Quaternion< Scalar >, Options > & unit_quaternion_nonconst ()
 

Protected Attributes

Map< Eigen::Quaternion< Scalar >, Options > unit_quaternion_
 

Friends

class Sophus::SO3Base< Map< Sophus::SO3< Scalar_ >, Options > >
 

Additional Inherited Members

- Static Public Attributes inherited from Sophus::SO3Base< Derived >
static constexpr int DoF = 3
 Degrees of freedom of group, number of dimensions in tangent space. More...
 
static constexpr int N = 3
 Group transformations are 3x3 matrices. More...
 
static constexpr int num_parameters = 4
 Number of internal parameters used (quaternion is a 4-tuple). More...
 

Detailed Description

template<class Scalar_, int Options>
class Eigen::Map< Sophus::SO3< Scalar_ >, Options >

Specialization of Eigen::Map for SO3; derived from SO3Base.

Allows us to wrap SO3 objects around POD array (e.g. external c style quaternion).

Definition at line 771 of file so3.hpp.

Member Typedef Documentation

◆ Adjoint

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Adjoint = typename Base::Adjoint

Definition at line 780 of file so3.hpp.

◆ Base

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Base = Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options> >

Definition at line 774 of file so3.hpp.

◆ HomogeneousPoint

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::HomogeneousPoint = typename Base::HomogeneousPoint

Definition at line 778 of file so3.hpp.

◆ Point

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Point = typename Base::Point

Definition at line 777 of file so3.hpp.

◆ Scalar

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Scalar = Scalar_

Definition at line 775 of file so3.hpp.

◆ Tangent

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Tangent = typename Base::Tangent

Definition at line 779 of file so3.hpp.

◆ Transformation

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Transformation = typename Base::Transformation

Definition at line 776 of file so3.hpp.

Constructor & Destructor Documentation

◆ Map()

template<class Scalar_ , int Options>
SOPHUS_FUNC Eigen::Map< Sophus::SO3< Scalar_ >, Options >::Map ( Scalar coeffs)
inline

Definition at line 793 of file so3.hpp.

Member Function Documentation

◆ EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR()

template<class Scalar_ , int Options>
Eigen::Map< Sophus::SO3< Scalar_ >, Options >::EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR ( Map< Sophus::SO3< Scalar_ >, Options >  )

◆ operator*() [1/4]

template<class Scalar_ , int Options>
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 4>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> Sophus::SO3Base< Derived >::operator* ( typename HPointDerived  ,
typename  = typename std::enable_if<                IsFixedSizeVector<HPointDerived, 4>::value>::type 
)
inline

Group action on homogeneous 3-points. See above for more details.

Definition at line 372 of file so3.hpp.

◆ operator*() [2/4]

template<class Scalar_ , int Options>
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 3>::value>::type>
SOPHUS_FUNC PointProduct<PointDerived> Sophus::SO3Base< Derived >::operator* ( typename PointDerived  ,
typename  = typename std::enable_if<                IsFixedSizeVector<PointDerived, 3>::value>::type 
)
inline

Group action on 3-points.

This function rotates a 3 dimensional point p by the SO3 element bar_R_foo (= rotation matrix): p_bar = bar_R_foo * p_foo.

Since SO3 is internally represented by a unit quaternion q, it is implemented as p_bar = q * p_foo * q^{*} with q^{*} being the quaternion conjugate of q.

Geometrically, p is rotated by angle |omega| around the axis omega/|omega| with omega := vee(log(bar_R_foo)).

For vee-operator, see below.

NOTE: We cannot use Eigen's Quaternion transformVector because it always returns a Vector3 of the same Scalar as this quaternion, so it is not able to be applied to Jets and doubles correctly.

Definition at line 357 of file so3.hpp.

◆ operator*() [3/4]

template<class Scalar_ , int Options>
SOPHUS_FUNC Line Sophus::SO3Base< Derived >::operator*
inline

Group action on lines.

This function rotates a parametrized line l(t) = o + t * d by the SO3 element:

Both direction d and origin o are rotated as a 3 dimensional point

Definition at line 385 of file so3.hpp.

◆ operator*() [4/4]

template<class Scalar_ , int Options>
template<typename OtherDerived >
SOPHUS_FUNC SO3Product<OtherDerived> Sophus::SO3Base< Derived >::operator* ( typename OtherDerived  )
inline

Group multiplication, which is rotation concatenation.

NOTE: We cannot use Eigen's Quaternion multiplication because it always returns a Quaternion of the same Scalar as this object, so it is not able to multiple Jets and doubles correctly.

Definition at line 324 of file so3.hpp.

◆ operator*=()

template<class Scalar_ , int Options>
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SO3Base<Derived>& Sophus::SO3Base< Derived >::operator*= ( typename OtherDerived  ,
typename  = typename std::enable_if<                std::is_same<ScalarReturnScalar<OtherDerived>>::value>::type 
)
inline

In-place group multiplication. This method is only valid if the return type of the multiplication is compatible with this SO3's Scalar type.

Definition at line 395 of file so3.hpp.

◆ unit_quaternion()

template<class Scalar_ , int Options>
SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options> const& Eigen::Map< Sophus::SO3< Scalar_ >, Options >::unit_quaternion ( ) const
inline

Accessor of unit quaternion.

Definition at line 797 of file so3.hpp.

◆ unit_quaternion_nonconst()

template<class Scalar_ , int Options>
SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options>& Eigen::Map< Sophus::SO3< Scalar_ >, Options >::unit_quaternion_nonconst ( )
inlineprotected

Mutator of unit_quaternion is protected to ensure class invariant.

Definition at line 806 of file so3.hpp.

Friends And Related Function Documentation

◆ Sophus::SO3Base< Map< Sophus::SO3< Scalar_ >, Options > >

template<class Scalar_ , int Options>
friend class Sophus::SO3Base< Map< Sophus::SO3< Scalar_ >, Options > >
friend

Base is friend so unit_quaternion_nonconst can be accessed from Base.

Definition at line 784 of file so3.hpp.

Member Data Documentation

◆ unit_quaternion_

template<class Scalar_ , int Options>
Map<Eigen::Quaternion<Scalar>, Options> Eigen::Map< Sophus::SO3< Scalar_ >, Options >::unit_quaternion_
protected

Definition at line 810 of file so3.hpp.


The documentation for this class was generated from the following file:


sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:48