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

#include <rxso3.hpp>

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

Public Types

using Adjoint = typename Base::Adjoint
 
using Base = Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, 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::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >
using Adjoint = Matrix< Scalar, DoF, DoF >
 
using HomogeneousPoint = Vector4< Scalar >
 
using HomogeneousPointProduct = Vector4< ReturnScalar< HPointDerived > >
 
using Line = ParametrizedLine3< Scalar >
 
using Point = Vector3< Scalar >
 
using PointProduct = Vector3< ReturnScalar< PointDerived > >
 
using QuaternionType = typename Eigen::internal::traits< Map< Sophus::RxSO3< Scalar_ > const, Options > >::QuaternionType
 
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType
 
using RxSO3Product = RxSO3< ReturnScalar< OtherDerived > >
 
using Scalar = typename Eigen::internal::traits< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Scalar
 
using Tangent = Vector< Scalar, DoF >
 
using Transformation = Matrix< Scalar, N, N >
 

Public Member Functions

SOPHUS_FUNC Map (Scalar const *coeffs)
 
SOPHUS_FUNC Map< Eigen::Quaternion< Scalar > const, Options > const & quaternion () const
 
- Public Member Functions inherited from Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >
SOPHUS_FUNC Adjoint Adj () const
 
SOPHUS_FUNC RxSO3< NewScalarType > cast () const
 
SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
SOPHUS_FUNC RxSO3< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC TangentAndTheta logAndTheta () const
 
SOPHUS_FUNC Transformation matrix () const
 
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
 
SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const
 
SOPHUS_FUNC Line operator* (Line const &l) const
 
SOPHUS_FUNC RxSO3Product< OtherDerived > operator* (RxSO3Base< OtherDerived > const &other) const
 
SOPHUS_FUNC RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > > & operator*= (RxSO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC RxSO3Baseoperator= (RxSO3Base const &other)=default
 
SOPHUS_FUNC RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > > & operator= (RxSO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC QuaternionType const & quaternion () const
 
SOPHUS_FUNC Transformation rotationMatrix () const
 
SOPHUS_FUNC Scalar scale () const
 
SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quat)
 
SOPHUS_FUNC void setRotationMatrix (Transformation const &R)
 
SOPHUS_FUNC void setScale (Scalar const &scale)
 
SOPHUS_FUNC void setScaledRotationMatrix (Transformation const &sR)
 
SOPHUS_FUNC void setSO3 (SO3< Scalar > const &so3)
 
SOPHUS_FUNC SO3< Scalarso3 () const
 

Protected Attributes

const Map< Eigen::Quaternion< Scalar > const, Options > quaternion_
 

Additional Inherited Members

- Static Public Attributes inherited from Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >
static constexpr int DoF
 
static constexpr int N
 Group transformations are 3x3 matrices. More...
 
static constexpr int num_parameters
 Number of internal parameters used (quaternion is a 4-tuple). More...
 
- Protected Member Functions inherited from Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >
SOPHUS_FUNC QuaternionTypequaternion_nonconst ()
 

Detailed Description

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

Specialization of Eigen::Map for RxSO3 const; derived from RxSO3Base.

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

Definition at line 696 of file rxso3.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 705 of file rxso3.hpp.

◆ Base

template<class Scalar_ , int Options>
using Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Base = Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_> const, Options> >

Definition at line 699 of file rxso3.hpp.

◆ HomogeneousPoint

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

Definition at line 703 of file rxso3.hpp.

◆ Point

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

Definition at line 702 of file rxso3.hpp.

◆ Scalar

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

Definition at line 700 of file rxso3.hpp.

◆ Tangent

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

Definition at line 704 of file rxso3.hpp.

◆ Transformation

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

Definition at line 701 of file rxso3.hpp.

Constructor & Destructor Documentation

◆ Map()

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

Definition at line 711 of file rxso3.hpp.

Member Function Documentation

◆ quaternion()

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

Accessor of quaternion.

Definition at line 716 of file rxso3.hpp.

Member Data Documentation

◆ quaternion_

template<class Scalar_ , int Options>
const Map<Eigen::Quaternion<Scalar> const, Options> Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::quaternion_
protected

Definition at line 721 of file rxso3.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