rxso3.hpp
Go to the documentation of this file.
1 
4 #ifndef SOPHUS_RXSO3_HPP
5 #define SOPHUS_RXSO3_HPP
6 
7 #include "so3.hpp"
8 
9 namespace Sophus {
10 template <class Scalar_, int Options = 0>
11 class RxSO3;
14 } // namespace Sophus
15 
16 namespace Eigen {
17 namespace internal {
18 
19 template <class Scalar_, int Options>
20 struct traits<Sophus::RxSO3<Scalar_, Options>> {
21  using Scalar = Scalar_;
22  using QuaternionType = Eigen::Quaternion<Scalar, Options>;
23 };
24 
25 template <class Scalar_, int Options>
26 struct traits<Map<Sophus::RxSO3<Scalar_>, Options>>
27  : traits<Sophus::RxSO3<Scalar_, Options>> {
28  using Scalar = Scalar_;
29  using QuaternionType = Map<Eigen::Quaternion<Scalar>, Options>;
30 };
31 
32 template <class Scalar_, int Options>
33 struct traits<Map<Sophus::RxSO3<Scalar_> const, Options>>
34  : traits<Sophus::RxSO3<Scalar_, Options> const> {
35  using Scalar = Scalar_;
36  using QuaternionType = Map<Eigen::Quaternion<Scalar> const, Options>;
37 };
38 } // namespace internal
39 } // namespace Eigen
40 
41 namespace Sophus {
42 
66 template <class Derived>
67 class RxSO3Base {
68  public:
69  using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
70  using QuaternionType =
71  typename Eigen::internal::traits<Derived>::QuaternionType;
72 
75  static int constexpr DoF = 4;
77  static int constexpr num_parameters = 4;
79  static int constexpr N = 3;
86 
87  struct TangentAndTheta {
88  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
89 
92  };
93 
98  template <typename OtherDerived>
99  using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
100  Scalar, typename OtherDerived::Scalar>::ReturnType;
101 
102  template <typename OtherDerived>
104 
105  template <typename PointDerived>
107 
108  template <typename HPointDerived>
110 
120  Adjoint res;
121  res.setIdentity();
122  res.template topLeftCorner<3, 3>() = rotationMatrix();
123  return res;
124  }
125 
128  template <class NewScalarType>
130  return RxSO3<NewScalarType>(quaternion().template cast<NewScalarType>());
131  }
132 
141  SOPHUS_FUNC Scalar* data() { return quaternion_nonconst().coeffs().data(); }
142 
145  SOPHUS_FUNC Scalar const* data() const {
146  return quaternion().coeffs().data();
147  }
148 
152  return RxSO3<Scalar>(quaternion().inverse());
153  }
154 
165  SOPHUS_FUNC Tangent log() const { return logAndTheta().tangent; }
166 
169  SOPHUS_FUNC TangentAndTheta logAndTheta() const {
170  using std::log;
171 
172  Scalar scale = quaternion().squaredNorm();
173  TangentAndTheta result;
174  result.tangent[3] = log(scale);
175  auto omega_and_theta = SO3<Scalar>(quaternion()).logAndTheta();
176  result.tangent.template head<3>() = omega_and_theta.tangent;
177  result.theta = omega_and_theta.theta;
178  return result;
179  }
187  Transformation sR;
188 
189  Scalar const vx_sq = quaternion().vec().x() * quaternion().vec().x();
190  Scalar const vy_sq = quaternion().vec().y() * quaternion().vec().y();
191  Scalar const vz_sq = quaternion().vec().z() * quaternion().vec().z();
192  Scalar const w_sq = quaternion().w() * quaternion().w();
193  Scalar const two_vx = Scalar(2) * quaternion().vec().x();
194  Scalar const two_vy = Scalar(2) * quaternion().vec().y();
195  Scalar const two_vz = Scalar(2) * quaternion().vec().z();
196  Scalar const two_vx_vy = two_vx * quaternion().vec().y();
197  Scalar const two_vx_vz = two_vx * quaternion().vec().z();
198  Scalar const two_vx_w = two_vx * quaternion().w();
199  Scalar const two_vy_vz = two_vy * quaternion().vec().z();
200  Scalar const two_vy_w = two_vy * quaternion().w();
201  Scalar const two_vz_w = two_vz * quaternion().w();
202 
203  sR(0, 0) = vx_sq - vy_sq - vz_sq + w_sq;
204  sR(1, 0) = two_vx_vy + two_vz_w;
205  sR(2, 0) = two_vx_vz - two_vy_w;
206 
207  sR(0, 1) = two_vx_vy - two_vz_w;
208  sR(1, 1) = -vx_sq + vy_sq - vz_sq + w_sq;
209  sR(2, 1) = two_vx_w + two_vy_vz;
210 
211  sR(0, 2) = two_vx_vz + two_vy_w;
212  sR(1, 2) = -two_vx_w + two_vy_vz;
213  sR(2, 2) = -vx_sq - vy_sq + vz_sq + w_sq;
214  return sR;
215  }
216 
219  SOPHUS_FUNC RxSO3Base& operator=(RxSO3Base const& other) = default;
220 
223  template <class OtherDerived>
225  RxSO3Base<OtherDerived> const& other) {
226  quaternion_nonconst() = other.quaternion();
227  return *this;
228  }
229 
236  template <typename OtherDerived>
238  RxSO3Base<OtherDerived> const& other) const {
239  using ResultT = ReturnScalar<OtherDerived>;
240  typename RxSO3Product<OtherDerived>::QuaternionType result_quaternion(
241  quaternion() * other.quaternion());
242 
243  ResultT scale = result_quaternion.squaredNorm();
245  SOPHUS_ENSURE(scale > ResultT(0), "Scale must be greater zero.");
247  result_quaternion.normalize();
248  result_quaternion.coeffs() *= sqrt(Constants<Scalar>::epsilon());
249  }
250  return RxSO3Product<OtherDerived>(result_quaternion);
251  }
252 
261  template <typename PointDerived,
262  typename = typename std::enable_if<
265  Eigen::MatrixBase<PointDerived> const& p) const {
266  // Follows http:///eigen.tuxfamily.org/bz/show_bug.cgi?id=459
267  Scalar scale = quaternion().squaredNorm();
268  PointProduct<PointDerived> two_vec_cross_p = quaternion().vec().cross(p);
269  two_vec_cross_p += two_vec_cross_p;
270  return scale * p + (quaternion().w() * two_vec_cross_p +
271  quaternion().vec().cross(two_vec_cross_p));
272  }
273 
276  template <typename HPointDerived,
277  typename = typename std::enable_if<
280  Eigen::MatrixBase<HPointDerived> const& p) const {
281  const auto rsp = *this * p.template head<3>();
282  return HomogeneousPointProduct<HPointDerived>(rsp(0), rsp(1), rsp(2), p(3));
283  }
284 
293  SOPHUS_FUNC Line operator*(Line const& l) const {
294  return Line((*this) * l.origin(),
295  (*this) * l.direction() / quaternion().squaredNorm());
296  }
297 
304  template <typename OtherDerived,
305  typename = typename std::enable_if<
306  std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
308  RxSO3Base<OtherDerived> const& other) {
309  *static_cast<Derived*>(this) = *this * other;
310  return *this;
311  }
312 
319  return quaternion().coeffs();
320  }
321 
325  SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quat) {
326  SOPHUS_ENSURE(quat.squaredNorm() > Constants<Scalar>::epsilon() *
328  "Scale factor must be greater-equal epsilon.");
329  static_cast<Derived*>(this)->quaternion_nonconst() = quat;
330  }
331 
335  return static_cast<Derived const*>(this)->quaternion();
336  }
337 
341  QuaternionType norm_quad = quaternion();
342  norm_quad.normalize();
343  return norm_quad.toRotationMatrix();
344  }
345 
349  Scalar scale() const { return quaternion().squaredNorm(); }
350 
354  using std::sqrt;
355  Scalar saved_scale = scale();
356  quaternion_nonconst() = R;
357  quaternion_nonconst().coeffs() *= sqrt(saved_scale);
358  }
359 
366  void setScale(Scalar const& scale) {
367  using std::sqrt;
368  quaternion_nonconst().normalize();
369  quaternion_nonconst().coeffs() *= sqrt(scale);
370  }
371 
378  Transformation squared_sR = sR * sR.transpose();
379  Scalar squared_scale =
380  Scalar(1. / 3.) *
381  (squared_sR(0, 0) + squared_sR(1, 1) + squared_sR(2, 2));
382  SOPHUS_ENSURE(squared_scale >= Constants<Scalar>::epsilon() *
384  "Scale factor must be greater-equal epsilon.");
385  Scalar scale = sqrt(squared_scale);
386  quaternion_nonconst() = sR / scale;
387  quaternion_nonconst().coeffs() *= sqrt(scale);
388  }
389 
393  using std::sqrt;
394  Scalar saved_scale = scale();
395  quaternion_nonconst() = so3.unit_quaternion();
396  quaternion_nonconst().coeffs() *= sqrt(saved_scale);
397  }
398 
400 
401  protected:
405  return static_cast<Derived*>(this)->quaternion_nonconst();
406  }
407 };
408 
410 template <class Scalar_, int Options>
411 class RxSO3 : public RxSO3Base<RxSO3<Scalar_, Options>> {
412  public:
414  using Scalar = Scalar_;
416  using Point = typename Base::Point;
418  using Tangent = typename Base::Tangent;
419  using Adjoint = typename Base::Adjoint;
420  using QuaternionMember = Eigen::Quaternion<Scalar, Options>;
421 
423  friend class RxSO3Base<RxSO3<Scalar_, Options>>;
424 
425  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
426 
431  : quaternion_(Scalar(1), Scalar(0), Scalar(0), Scalar(0)) {}
432 
435  SOPHUS_FUNC RxSO3(RxSO3 const& other) = default;
436 
439  template <class OtherDerived>
441  : quaternion_(other.quaternion()) {}
442 
448  SOPHUS_FUNC explicit RxSO3(Transformation const& sR) {
449  this->setScaledRotationMatrix(sR);
450  }
451 
457  SOPHUS_FUNC RxSO3(Scalar const& scale, Transformation const& R)
458  : quaternion_(R) {
460  "Scale factor must be greater-equal epsilon.");
461  using std::sqrt;
462  quaternion_.coeffs() *= sqrt(scale);
463  }
464 
469  SOPHUS_FUNC RxSO3(Scalar const& scale, SO3<Scalar> const& so3)
470  : quaternion_(so3.unit_quaternion()) {
472  "Scale factor must be greater-equal epsilon.");
473  using std::sqrt;
474  quaternion_.coeffs() *= sqrt(scale);
475  }
476 
481  template <class D>
482  SOPHUS_FUNC explicit RxSO3(Eigen::QuaternionBase<D> const& quat)
483  : quaternion_(quat) {
484  static_assert(std::is_same<typename D::Scalar, Scalar>::value,
485  "must be same Scalar type.");
487  "Scale factor must be greater-equal epsilon.");
488  }
489 
493 
497  return generator(i);
498  }
510  Scalar theta;
511  return expAndTheta(a, &theta);
512  }
513 
519  Scalar* theta) {
520  SOPHUS_ENSURE(theta != nullptr, "must not be nullptr.");
521  using std::exp;
522  using std::sqrt;
523 
524  Vector3<Scalar> const omega = a.template head<3>();
525  Scalar sigma = a[3];
526  Scalar sqrt_scale = sqrt(exp(sigma));
527  Eigen::Quaternion<Scalar> quat =
528  SO3<Scalar>::expAndTheta(omega, theta).unit_quaternion();
529  quat.coeffs() *= sqrt_scale;
530  return RxSO3<Scalar>(quat);
531  }
532 
558  SOPHUS_ENSURE(i >= 0 && i <= 3, "i should be in range [0,3].");
559  Tangent e;
560  e.setZero();
561  e[i] = Scalar(1);
562  return hat(e);
563  }
564 
580  Transformation A;
581  // clang-format off
582  A << a(3), -a(2), a(1),
583  a(2), a(3), -a(0),
584  -a(1), a(0), a(3);
585  // clang-format on
586  return A;
587  }
588 
598  SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
599  Vector3<Scalar> const omega1 = a.template head<3>();
600  Vector3<Scalar> const omega2 = b.template head<3>();
601  Vector4<Scalar> res;
602  res.template head<3>() = omega1.cross(omega2);
603  res[3] = Scalar(0);
604  return res;
605  }
606 
612  template <class UniformRandomBitGenerator>
613  static RxSO3 sampleUniform(UniformRandomBitGenerator& generator) {
614  std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
615  using std::exp2;
616  return RxSO3(exp2(uniform(generator)),
618  }
619 
633  SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
634  using std::abs;
635  return Tangent(Omega(2, 1), Omega(0, 2), Omega(1, 0), Omega(0, 0));
636  }
637 
638  protected:
640 
642 };
643 
644 } // namespace Sophus
645 
646 namespace Eigen {
647 
652 template <class Scalar_, int Options>
653 class Map<Sophus::RxSO3<Scalar_>, Options>
654  : public Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>> {
655  public:
657  using Scalar = Scalar_;
659  using Point = typename Base::Point;
661  using Tangent = typename Base::Tangent;
662  using Adjoint = typename Base::Adjoint;
663 
665  friend class Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>>;
666 
667  // LCOV_EXCL_START
668  EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map);
669  // LCOV_EXCL_STOP
670 
671  using Base::operator*=;
672  using Base::operator*;
673 
674  SOPHUS_FUNC Map(Scalar* coeffs) : quaternion_(coeffs) {}
675 
679  Map<Eigen::Quaternion<Scalar>, Options> const& quaternion() const {
680  return quaternion_;
681  }
682 
683  protected:
684  SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options>& quaternion_nonconst() {
685  return quaternion_;
686  }
687 
688  Map<Eigen::Quaternion<Scalar>, Options> quaternion_;
689 };
690 
695 template <class Scalar_, int Options>
696 class Map<Sophus::RxSO3<Scalar_> const, Options>
697  : public Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_> const, Options>> {
698  public:
700  using Scalar = Scalar_;
702  using Point = typename Base::Point;
704  using Tangent = typename Base::Tangent;
705  using Adjoint = typename Base::Adjoint;
706 
707  using Base::operator*=;
708  using Base::operator*;
709 
711  Map(Scalar const* coeffs) : quaternion_(coeffs) {}
712 
716  Map<Eigen::Quaternion<Scalar> const, Options> const& quaternion() const {
717  return quaternion_;
718  }
719 
720  protected:
721  Map<Eigen::Quaternion<Scalar> const, Options> const quaternion_;
722 };
723 } // namespace Eigen
724 
725 #endif
result
result[0]
Definition: Se2_Dx_exp_x.cpp:11
Sophus::RxSO3::quaternion
SOPHUS_FUNC QuaternionMember const & quaternion() const
Definition: rxso3.hpp:492
Sophus::RxSO3Base::DoF
static constexpr int DoF
Definition: rxso3.hpp:75
Eigen
Definition: rxso2.hpp:16
Sophus::RxSO3< Scalar, Options >::Scalar
Scalar Scalar
Definition: rxso3.hpp:414
Sophus::RxSO3Base::cast
SOPHUS_FUNC RxSO3< NewScalarType > cast() const
Definition: rxso3.hpp:129
Sophus::RxSO3Base::operator=
SOPHUS_FUNC RxSO3Base< Derived > & operator=(RxSO3Base< OtherDerived > const &other)
Definition: rxso3.hpp:224
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Adjoint
Matrix< Scalar, DoF, DoF > Adjoint
Definition: rxso3.hpp:85
Sophus::RxSO3Base::operator*=
SOPHUS_FUNC RxSO3Base< Derived > & operator*=(RxSO3Base< OtherDerived > const &other)
Definition: rxso3.hpp:307
Sophus::RxSO3::exp
static SOPHUS_FUNC RxSO3< Scalar > exp(Tangent const &a)
Definition: rxso3.hpp:509
Sophus::RxSO3Base::inverse
SOPHUS_FUNC RxSO3< Scalar > inverse() const
Definition: rxso3.hpp:151
Sophus::SO3
SO3 using default storage; derived from SO3Base.
Definition: so3.hpp:19
Sophus::RxSO3::sampleUniform
static RxSO3 sampleUniform(UniformRandomBitGenerator &generator)
Definition: rxso3.hpp:613
Sophus::RxSO3< Scalar, Options >::Adjoint
typename Base::Adjoint Adjoint
Definition: rxso3.hpp:419
Sophus::RxSO3Base::setScale
SOPHUS_FUNC void setScale(Scalar const &scale)
Definition: rxso3.hpp:366
Eigen::internal::traits< Sophus::RxSO3< Scalar_, Options > >::Scalar
Scalar_ Scalar
Definition: rxso3.hpp:21
Sophus::RxSO3Base::operator=
SOPHUS_FUNC RxSO3Base & operator=(RxSO3Base const &other)=default
Sophus::RxSO3< Scalar, Options >::HomogeneousPoint
typename Base::HomogeneousPoint HomogeneousPoint
Definition: rxso3.hpp:417
Sophus::Vector3
Vector< Scalar, 3, Options > Vector3
Definition: types.hpp:21
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::quaternion_
Map< Eigen::Quaternion< Scalar >, Options > quaternion_
Definition: rxso3.hpp:688
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Transformation
Matrix< Scalar, N, N > Transformation
Definition: rxso3.hpp:80
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::HomogeneousPointProduct
Vector4< ReturnScalar< HPointDerived > > HomogeneousPointProduct
Definition: rxso3.hpp:109
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::QuaternionType
typename Eigen::internal::traits< Map< Sophus::RxSO3< Scalar_ > const, Options > >::QuaternionType QuaternionType
Definition: rxso3.hpp:71
SOPHUS_ENSURE
#define SOPHUS_ENSURE(expr,...)
Definition: common.hpp:137
Sophus::RxSO3::lieBracket
static SOPHUS_FUNC Tangent lieBracket(Tangent const &a, Tangent const &b)
Definition: rxso3.hpp:598
Sophus::RxSO3Base::num_parameters
static constexpr int num_parameters
Number of internal parameters used (quaternion is a 4-tuple).
Definition: rxso3.hpp:77
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Tangent
Vector< Scalar, DoF > Tangent
Definition: rxso3.hpp:84
Sophus::RxSO3Base::params
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params() const
Definition: rxso3.hpp:318
Sophus::RxSO3::quaternion_
QuaternionMember quaternion_
Definition: rxso3.hpp:641
Sophus::RxSO3Base::logAndTheta
SOPHUS_FUNC TangentAndTheta logAndTheta() const
Definition: rxso3.hpp:169
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Map
SOPHUS_FUNC Map(Scalar const *coeffs)
Definition: rxso3.hpp:711
Sophus::RxSO3Base::TangentAndTheta::tangent
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Tangent tangent
Definition: rxso3.hpp:90
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::quaternion_
const Map< Eigen::Quaternion< Scalar > const, Options > quaternion_
Definition: rxso3.hpp:721
Sophus::RxSO3Base::setScaledRotationMatrix
SOPHUS_FUNC void setScaledRotationMatrix(Transformation const &sR)
Definition: rxso3.hpp:377
Eigen::internal::traits< Sophus::RxSO3< Scalar_, Options > >::QuaternionType
Eigen::Quaternion< Scalar, Options > QuaternionType
Definition: rxso3.hpp:22
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Point
typename Base::Point Point
Definition: rxso3.hpp:702
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Transformation
typename Base::Transformation Transformation
Definition: rxso3.hpp:701
Sophus::RxSO3Base::ReturnScalar
typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType ReturnScalar
Definition: rxso3.hpp:100
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::HomogeneousPoint
typename Base::HomogeneousPoint HomogeneousPoint
Definition: rxso3.hpp:703
Sophus::ParametrizedLine3
ParametrizedLine< Scalar, 3, Options > ParametrizedLine3
Definition: types.hpp:72
Sophus::RxSO3Base::so3
SOPHUS_FUNC SO3< Scalar > so3() const
Definition: rxso3.hpp:399
so3.hpp
Sophus::RxSO3::expAndTheta
static SOPHUS_FUNC RxSO3< Scalar > expAndTheta(Tangent const &a, Scalar *theta)
Definition: rxso3.hpp:518
Sophus::RxSO3::RxSO3
SOPHUS_FUNC RxSO3(Scalar const &scale, Transformation const &R)
Definition: rxso3.hpp:457
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::PointProduct
Vector3< ReturnScalar< PointDerived > > PointProduct
Definition: rxso3.hpp:106
Sophus::RxSO3Base::setRotationMatrix
SOPHUS_FUNC void setRotationMatrix(Transformation const &R)
Definition: rxso3.hpp:353
Sophus::RxSO3Base::operator*
SOPHUS_FUNC PointProduct< PointDerived > operator*(Eigen::MatrixBase< PointDerived > const &p) const
Definition: rxso3.hpp:264
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Adjoint
typename Base::Adjoint Adjoint
Definition: rxso3.hpp:705
Sophus::RxSO3Base::operator*
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator*(Eigen::MatrixBase< HPointDerived > const &p) const
Definition: rxso3.hpp:279
Sophus::RxSO3Base::TangentAndTheta
Definition: rxso3.hpp:87
Sophus::RxSO3Base::TangentAndTheta::theta
Scalar theta
Definition: rxso3.hpp:91
Sophus::RxSO3::RxSO3
SOPHUS_FUNC RxSO3(Eigen::QuaternionBase< D > const &quat)
Definition: rxso3.hpp:482
Sophus::Matrix
Eigen::Matrix< Scalar, M, N > Matrix
Definition: types.hpp:41
Sophus
Definition: average.hpp:17
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::quaternion_nonconst
SOPHUS_FUNC Map< Eigen::Quaternion< Scalar >, Options > & quaternion_nonconst()
Definition: rxso3.hpp:684
SOPHUS_FUNC
#define SOPHUS_FUNC
Definition: common.hpp:37
Sophus::RxSO3::hat
static SOPHUS_FUNC Transformation hat(Tangent const &a)
Definition: rxso3.hpp:579
Sophus::RxSO3< Scalar, Options >::Tangent
typename Base::Tangent Tangent
Definition: rxso3.hpp:418
Sophus::RxSO3Base::setQuaternion
SOPHUS_FUNC void setQuaternion(Eigen::Quaternion< Scalar > const &quat)
Definition: rxso3.hpp:325
Sophus::RxSO3Base::quaternion_nonconst
SOPHUS_FUNC QuaternionType & quaternion_nonconst()
Definition: rxso3.hpp:404
Sophus::RxSO3Base::data
SOPHUS_FUNC Scalar * data()
Definition: rxso3.hpp:141
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::HomogeneousPoint
typename Base::HomogeneousPoint HomogeneousPoint
Definition: rxso3.hpp:660
Eigen::internal::traits< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Scalar
Scalar_ Scalar
Definition: rxso3.hpp:35
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Scalar
Scalar_ Scalar
Definition: rxso3.hpp:700
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::quaternion
SOPHUS_FUNC Map< Eigen::Quaternion< Scalar >, Options > const & quaternion() const
Definition: rxso3.hpp:679
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::Scalar
Scalar_ Scalar
Definition: rxso3.hpp:657
Sophus::RxSO3Base
Definition: rxso3.hpp:67
Sophus::RxSO3< Scalar, Options >::Point
typename Base::Point Point
Definition: rxso3.hpp:416
Sophus::RxSO3Base::operator*
SOPHUS_FUNC Line operator*(Line const &l) const
Definition: rxso3.hpp:293
Sophus::RxSO3::Dxi_exp_x_matrix_at_0
static SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0(int i)
Definition: rxso3.hpp:496
Sophus::RxSO3< Scalar, Options >::Transformation
typename Base::Transformation Transformation
Definition: rxso3.hpp:415
Sophus::RxSO3::quaternion_nonconst
SOPHUS_FUNC QuaternionMember & quaternion_nonconst()
Definition: rxso3.hpp:639
Sophus::RxSO3Base::rotationMatrix
SOPHUS_FUNC Transformation rotationMatrix() const
Definition: rxso3.hpp:340
Sophus::RxSO3::generator
static SOPHUS_FUNC Transformation generator(int i)
Definition: rxso3.hpp:557
Sophus::IsFixedSizeVector
Definition: types.hpp:225
Sophus::Constants
Definition: common.hpp:146
Sophus::RxSO3< Scalar, Options >::QuaternionMember
Eigen::Quaternion< Scalar, Options > QuaternionMember
Definition: rxso3.hpp:420
Sophus::squaredNorm
auto squaredNorm(T const &p) -> decltype(details::SquaredNorm< T >::impl(p))
Definition: types.hpp:187
Sophus::RxSO3Base::Adj
SOPHUS_FUNC Adjoint Adj() const
Definition: rxso3.hpp:119
Sophus::RxSO3Base::log
SOPHUS_FUNC Tangent log() const
Definition: rxso3.hpp:165
Sophus::Vector4
Vector< Scalar, 4 > Vector4
Definition: types.hpp:26
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::Point
typename Base::Point Point
Definition: rxso3.hpp:659
Sophus::RxSO3Base::N
static constexpr int N
Group transformations are 3x3 matrices.
Definition: rxso3.hpp:79
Eigen::internal::traits< Map< Sophus::RxSO3< Scalar_ > const, Options > >::QuaternionType
Map< Eigen::Quaternion< Scalar > const, Options > QuaternionType
Definition: rxso3.hpp:36
Sophus::RxSO3::vee
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
Definition: rxso3.hpp:633
Sophus::Vector
Eigen::Matrix< Scalar, M, 1, Options > Vector
Definition: types.hpp:13
Sophus::RxSO3Base::operator*
SOPHUS_FUNC RxSO3Product< OtherDerived > operator*(RxSO3Base< OtherDerived > const &other) const
Definition: rxso3.hpp:237
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Point
Vector3< Scalar > Point
Definition: rxso3.hpp:81
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::Adjoint
typename Base::Adjoint Adjoint
Definition: rxso3.hpp:662
Sophus::RxSO3Base::matrix
SOPHUS_FUNC Transformation matrix() const
Definition: rxso3.hpp:186
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::Transformation
typename Base::Transformation Transformation
Definition: rxso3.hpp:658
Sophus::SO3::expAndTheta
static SOPHUS_FUNC SO3< Scalar > expAndTheta(Tangent const &omega, Scalar *theta)
Definition: so3.hpp:580
Sophus::RxSO3::RxSO3
SOPHUS_FUNC RxSO3(Transformation const &sR)
Definition: rxso3.hpp:448
Sophus::RxSO3::RxSO3
SOPHUS_FUNC RxSO3(RxSO3Base< OtherDerived > const &other)
Definition: rxso3.hpp:440
Sophus::RxSO3Base::data
SOPHUS_FUNC Scalar const * data() const
Definition: rxso3.hpp:145
Sophus::RxSO3Base::scale
SOPHUS_FUNC Scalar scale() const
Definition: rxso3.hpp:349
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::HomogeneousPoint
Vector4< Scalar > HomogeneousPoint
Definition: rxso3.hpp:82
Sophus::RxSO3
RxSO3 using storage; derived from RxSO3Base.
Definition: rxso3.hpp:11
Sophus::RxSO3Base::quaternion
SOPHUS_FUNC QuaternionType const & quaternion() const
Definition: rxso3.hpp:334
Sophus::RxSO3::RxSO3
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC RxSO3()
Definition: rxso3.hpp:430
Sophus::RxSO3::RxSO3
SOPHUS_FUNC RxSO3(Scalar const &scale, SO3< Scalar > const &so3)
Definition: rxso3.hpp:469
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Line
ParametrizedLine3< Scalar > Line
Definition: rxso3.hpp:83
Sophus::RxSO3Base::setSO3
SOPHUS_FUNC void setSO3(SO3< Scalar > const &so3)
Definition: rxso3.hpp:392
Sophus::RxSO3Base< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Scalar
typename Eigen::internal::traits< Map< Sophus::RxSO3< Scalar_ > const, Options > >::Scalar Scalar
Definition: rxso3.hpp:69
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::quaternion
SOPHUS_FUNC Map< Eigen::Quaternion< Scalar > const, Options > const & quaternion() const
Definition: rxso3.hpp:716
Eigen::Map< Sophus::RxSO3< Scalar_ > const, Options >::Tangent
typename Base::Tangent Tangent
Definition: rxso3.hpp:704
Eigen::Map< Sophus::RxSO3< Scalar_ >, Options >::Tangent
typename Base::Tangent Tangent
Definition: rxso3.hpp:661


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