se2.hpp
Go to the documentation of this file.
1 
4 #ifndef SOPHUS_SE2_HPP
5 #define SOPHUS_SE2_HPP
6 
7 #include "so2.hpp"
8 
9 namespace Sophus {
10 template <class Scalar_, int Options = 0>
11 class SE2;
12 using SE2d = SE2<double>;
13 using SE2f = SE2<float>;
14 } // namespace Sophus
15 
16 namespace Eigen {
17 namespace internal {
18 
19 template <class Scalar_, int Options>
20 struct traits<Sophus::SE2<Scalar_, Options>> {
21  using Scalar = Scalar_;
24 };
25 
26 template <class Scalar_, int Options>
27 struct traits<Map<Sophus::SE2<Scalar_>, Options>>
28  : traits<Sophus::SE2<Scalar_, Options>> {
29  using Scalar = Scalar_;
30  using TranslationType = Map<Sophus::Vector2<Scalar>, Options>;
31  using SO2Type = Map<Sophus::SO2<Scalar>, Options>;
32 };
33 
34 template <class Scalar_, int Options>
35 struct traits<Map<Sophus::SE2<Scalar_> const, Options>>
36  : traits<Sophus::SE2<Scalar_, Options> const> {
37  using Scalar = Scalar_;
38  using TranslationType = Map<Sophus::Vector2<Scalar> const, Options>;
39  using SO2Type = Map<Sophus::SO2<Scalar> const, Options>;
40 };
41 } // namespace internal
42 } // namespace Eigen
43 
44 namespace Sophus {
45 
57 template <class Derived>
58 class SE2Base {
59  public:
60  using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
61  using TranslationType =
62  typename Eigen::internal::traits<Derived>::TranslationType;
63  using SO2Type = typename Eigen::internal::traits<Derived>::SO2Type;
64 
67  static int constexpr DoF = 3;
70  static int constexpr num_parameters = 4;
72  static int constexpr N = 3;
79 
84  template <typename OtherDerived>
85  using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
86  Scalar, typename OtherDerived::Scalar>::ReturnType;
87 
88  template <typename OtherDerived>
90 
91  template <typename PointDerived>
93 
94  template <typename HPointDerived>
96 
104  Matrix<Scalar, 2, 2> const& R = so2().matrix();
105  Transformation res;
106  res.setIdentity();
107  res.template topLeftCorner<2, 2>() = R;
108  res(0, 2) = translation()[1];
109  res(1, 2) = -translation()[0];
110  return res;
111  }
112 
115  template <class NewScalarType>
117  return SE2<NewScalarType>(so2().template cast<NewScalarType>(),
118  translation().template cast<NewScalarType>());
119  }
120 
124  const {
127  Scalar o(0);
128  J(0, 0) = o;
129  J(0, 1) = o;
130  J(0, 2) = -c[1];
131  J(1, 0) = o;
132  J(1, 1) = o;
133  J(1, 2) = c[0];
134  J(2, 0) = c[0];
135  J(2, 1) = -c[1];
136  J(2, 2) = o;
137  J(3, 0) = c[1];
138  J(3, 1) = c[0];
139  J(3, 2) = o;
140  return J;
141  }
142 
146  SO2<Scalar> const invR = so2().inverse();
147  return SE2<Scalar>(invR, invR * (translation() * Scalar(-1)));
148  }
149 
161  using std::abs;
162 
163  Tangent upsilon_theta;
164  Scalar theta = so2().log();
165  upsilon_theta[2] = theta;
166  Scalar halftheta = Scalar(0.5) * theta;
167  Scalar halftheta_by_tan_of_halftheta;
168 
169  Vector2<Scalar> z = so2().unit_complex();
170  Scalar real_minus_one = z.x() - Scalar(1.);
171  if (abs(real_minus_one) < Constants<Scalar>::epsilon()) {
172  halftheta_by_tan_of_halftheta =
173  Scalar(1.) - Scalar(1. / 12) * theta * theta;
174  } else {
175  halftheta_by_tan_of_halftheta = -(halftheta * z.y()) / (real_minus_one);
176  }
177  Matrix<Scalar, 2, 2> V_inv;
178  V_inv << halftheta_by_tan_of_halftheta, halftheta, -halftheta,
179  halftheta_by_tan_of_halftheta;
180  upsilon_theta.template head<2>() = V_inv * translation();
181  return upsilon_theta;
182  }
183 
188  SOPHUS_FUNC void normalize() { so2().normalize(); }
189 
201  Transformation homogenious_matrix;
202  homogenious_matrix.template topLeftCorner<2, 3>() = matrix2x3();
203  homogenious_matrix.row(2) =
205  return homogenious_matrix;
206  }
207 
212  matrix.template topLeftCorner<2, 2>() = rotationMatrix();
213  matrix.col(2) = translation();
214  return matrix;
215  }
216 
219  SOPHUS_FUNC SE2Base& operator=(SE2Base const& other) = default;
220 
223  template <class OtherDerived>
225  so2() = other.so2();
226  translation() = other.translation();
227  return *this;
228  }
229 
232  template <typename OtherDerived>
234  SE2Base<OtherDerived> const& other) const {
236  so2() * other.so2(), translation() + so2() * other.translation());
237  }
238 
247  template <typename PointDerived,
248  typename = typename std::enable_if<
251  Eigen::MatrixBase<PointDerived> const& p) const {
252  return so2() * p + translation();
253  }
254 
257  template <typename HPointDerived,
258  typename = typename std::enable_if<
261  Eigen::MatrixBase<HPointDerived> const& p) const {
262  const PointProduct<HPointDerived> tp =
263  so2() * p.template head<2>() + p(2) * translation();
264  return HomogeneousPointProduct<HPointDerived>(tp(0), tp(1), p(2));
265  }
266 
275  SOPHUS_FUNC Line operator*(Line const& l) const {
276  return Line((*this) * l.origin(), so2() * l.direction());
277  }
278 
282  template <typename OtherDerived,
283  typename = typename std::enable_if<
284  std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
286  *static_cast<Derived*>(this) = *this * other;
287  return *this;
288  }
289 
297  p << so2().params(), translation();
298  return p;
299  }
300 
304  return so2().matrix();
305  }
306 
312  return so2().setComplex(complex);
313  }
314 
320  SOPHUS_ENSURE(isOrthogonal(R), "R is not orthogonal:\n %", R);
321  SOPHUS_ENSURE(R.determinant() > Scalar(0), "det(R) is not positive: %",
322  R.determinant());
323  typename SO2Type::ComplexT const complex(Scalar(0.5) * (R(0, 0) + R(1, 1)),
324  Scalar(0.5) * (R(1, 0) - R(0, 1)));
325  so2().setComplex(complex);
326  }
327 
331  SO2Type& so2() { return static_cast<Derived*>(this)->so2(); }
332 
336  SO2Type const& so2() const {
337  return static_cast<Derived const*>(this)->so2();
338  }
339 
344  return static_cast<Derived*>(this)->translation();
345  }
346 
350  TranslationType const& translation() const {
351  return static_cast<Derived const*>(this)->translation();
352  }
353 
357  typename Eigen::internal::traits<Derived>::SO2Type::ComplexT const&
358  unit_complex() const {
359  return so2().unit_complex();
360  }
361 };
362 
364 template <class Scalar_, int Options>
365 class SE2 : public SE2Base<SE2<Scalar_, Options>> {
366  public:
368  static int constexpr DoF = Base::DoF;
369  static int constexpr num_parameters = Base::num_parameters;
370 
371  using Scalar = Scalar_;
373  using Point = typename Base::Point;
375  using Tangent = typename Base::Tangent;
376  using Adjoint = typename Base::Adjoint;
379 
380  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
381 
384  SOPHUS_FUNC SE2();
385 
388  SOPHUS_FUNC SE2(SE2 const& other) = default;
389 
392  template <class OtherDerived>
394  : so2_(other.so2()), translation_(other.translation()) {
395  static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
396  "must be same Scalar type");
397  }
398 
401  template <class OtherDerived, class D>
403  Eigen::MatrixBase<D> const& translation)
405  static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
406  "must be same Scalar type");
407  static_assert(std::is_same<typename D::Scalar, Scalar>::value,
408  "must be same Scalar type");
409  }
410 
417  SE2(typename SO2<Scalar>::Transformation const& rotation_matrix,
418  Point const& translation)
419  : so2_(rotation_matrix), translation_(translation) {}
420 
423  SOPHUS_FUNC SE2(Scalar const& theta, Point const& translation)
424  : so2_(theta), translation_(translation) {}
425 
430  : so2_(complex), translation_(translation) {}
431 
437  SOPHUS_FUNC explicit SE2(Transformation const& T)
438  : so2_(T.template topLeftCorner<2, 2>().eval()),
439  translation_(T.template block<2, 1>(0, 2)) {}
440 
447  // so2_ and translation_ are layed out sequentially with no padding
448  return so2_.data();
449  }
450 
453  SOPHUS_FUNC Scalar const* data() const {
455  return so2_.data();
456  }
457 
460  SOPHUS_FUNC SO2Member& so2() { return so2_; }
461 
464  SOPHUS_FUNC SO2Member const& so2() const { return so2_; }
465 
469 
473  return translation_;
474  }
475 
479  Tangent const& upsilon_theta) {
480  using std::abs;
481  using std::cos;
482  using std::pow;
483  using std::sin;
485  Sophus::Vector<Scalar, 2> upsilon = upsilon_theta.template head<2>();
486  Scalar theta = upsilon_theta[2];
487 
488  if (abs(theta) < Constants<Scalar>::epsilon()) {
489  Scalar const o(0);
490  Scalar const i(1);
491 
492  // clang-format off
493  J << o, o, o, o, o, i, i, o, -Scalar(0.5) * upsilon[1], o, i,
494  Scalar(0.5) * upsilon[0];
495  // clang-format on
496  return J;
497  }
498 
499  Scalar const c0 = sin(theta);
500  Scalar const c1 = cos(theta);
501  Scalar const c2 = 1.0 / theta;
502  Scalar const c3 = c0 * c2;
503  Scalar const c4 = -c1 + Scalar(1);
504  Scalar const c5 = c2 * c4;
505  Scalar const c6 = c1 * c2;
506  Scalar const c7 = pow(theta, -2);
507  Scalar const c8 = c0 * c7;
508  Scalar const c9 = c4 * c7;
509 
510  Scalar const o = Scalar(0);
511  J(0, 0) = o;
512  J(0, 1) = o;
513  J(0, 2) = -c0;
514  J(1, 0) = o;
515  J(1, 1) = o;
516  J(1, 2) = c1;
517  J(2, 0) = c3;
518  J(2, 1) = -c5;
519  J(2, 2) =
520  -c3 * upsilon[1] + c6 * upsilon[0] - c8 * upsilon[0] + c9 * upsilon[1];
521  J(3, 0) = c5;
522  J(3, 1) = c3;
523  J(3, 2) =
524  c3 * upsilon[0] + c6 * upsilon[1] - c8 * upsilon[1] - c9 * upsilon[0];
525  return J;
526  }
527 
533  Scalar const o(0);
534  Scalar const i(1);
535 
536  // clang-format off
537  J << o, o, o, o, o, i, i, o, o, o, i, o;
538  // clang-format on
539  return J;
540  }
541 
545  return generator(i);
546  }
547 
560  SOPHUS_FUNC static SE2<Scalar> exp(Tangent const& a) {
561  Scalar theta = a[2];
563  Scalar sin_theta_by_theta;
564  Scalar one_minus_cos_theta_by_theta;
565  using std::abs;
566 
567  if (abs(theta) < Constants<Scalar>::epsilon()) {
568  Scalar theta_sq = theta * theta;
569  sin_theta_by_theta = Scalar(1.) - Scalar(1. / 6.) * theta_sq;
570  one_minus_cos_theta_by_theta =
571  Scalar(0.5) * theta - Scalar(1. / 24.) * theta * theta_sq;
572  } else {
573  sin_theta_by_theta = so2.unit_complex().y() / theta;
574  one_minus_cos_theta_by_theta =
575  (Scalar(1.) - so2.unit_complex().x()) / theta;
576  }
578  sin_theta_by_theta * a[0] - one_minus_cos_theta_by_theta * a[1],
579  one_minus_cos_theta_by_theta * a[0] + sin_theta_by_theta * a[1]);
580  return SE2<Scalar>(so2, trans);
581  }
582 
585  template <class S = Scalar>
588  return SE2(SO2<Scalar>::fitToSO2(T.template block<2, 2>(0, 0)),
589  T.template block<2, 1>(0, 2));
590  }
591 
613  SOPHUS_ENSURE(i >= 0 || i <= 2, "i should be in range [0,2].");
614  Tangent e;
615  e.setZero();
616  e[i] = Scalar(1);
617  return hat(e);
618  }
619 
634  Transformation Omega;
635  Omega.setZero();
636  Omega.template topLeftCorner<2, 2>() = SO2<Scalar>::hat(a[2]);
637  Omega.col(2).template head<2>() = a.template head<2>();
638  return Omega;
639  }
640 
650  SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
651  Vector2<Scalar> upsilon1 = a.template head<2>();
652  Vector2<Scalar> upsilon2 = b.template head<2>();
653  Scalar theta1 = a[2];
654  Scalar theta2 = b[2];
655 
656  return Tangent(-theta1 * upsilon2[1] + theta2 * upsilon1[1],
657  theta1 * upsilon2[0] - theta2 * upsilon1[0], Scalar(0));
658  }
659 
662  static SOPHUS_FUNC SE2 rot(Scalar const& x) {
664  }
665 
670  template <class UniformRandomBitGenerator>
671  static SE2 sampleUniform(UniformRandomBitGenerator& generator) {
672  std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
674  Vector2<Scalar>(uniform(generator), uniform(generator)));
675  }
676 
679  template <class T0, class T1>
680  static SOPHUS_FUNC SE2 trans(T0 const& x, T1 const& y) {
681  return SE2(SO2<Scalar>(), Vector2<Scalar>(x, y));
682  }
683 
684  static SOPHUS_FUNC SE2 trans(Vector2<Scalar> const& xy) {
685  return SE2(SO2<Scalar>(), xy);
686  }
687 
690  static SOPHUS_FUNC SE2 transX(Scalar const& x) {
691  return SE2::trans(x, Scalar(0));
692  }
693 
696  static SOPHUS_FUNC SE2 transY(Scalar const& y) {
697  return SE2::trans(Scalar(0), y);
698  }
699 
713  SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
715  Omega.row(2).template lpNorm<1>() < Constants<Scalar>::epsilon(),
716  "Omega: \n%", Omega);
717  Tangent upsilon_omega;
718  upsilon_omega.template head<2>() = Omega.col(2).template head<2>();
719  upsilon_omega[2] = SO2<Scalar>::vee(Omega.template topLeftCorner<2, 2>());
720  return upsilon_omega;
721  }
722 
723  protected:
726 };
727 
728 template <class Scalar, int Options>
729 SE2<Scalar, Options>::SE2() : translation_(TranslationMember::Zero()) {
730  static_assert(std::is_standard_layout<SE2>::value,
731  "Assume standard layout for the use of offsetof check below.");
732  static_assert(
733  offsetof(SE2, so2_) + sizeof(Scalar) * SO2<Scalar>::num_parameters ==
734  offsetof(SE2, translation_),
735  "This class assumes packed storage and hence will only work "
736  "correctly depending on the compiler (options) - in "
737  "particular when using [this->data(), this-data() + "
738  "num_parameters] to access the raw data in a contiguous fashion.");
739 }
740 
741 } // namespace Sophus
742 
743 namespace Eigen {
744 
748 template <class Scalar_, int Options>
749 class Map<Sophus::SE2<Scalar_>, Options>
750  : public Sophus::SE2Base<Map<Sophus::SE2<Scalar_>, Options>> {
751  public:
753  using Scalar = Scalar_;
755  using Point = typename Base::Point;
757  using Tangent = typename Base::Tangent;
758  using Adjoint = typename Base::Adjoint;
759 
760  // LCOV_EXCL_START
761  EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map);
762  // LCOV_EXCL_STOP
763 
764  using Base::operator*=;
765  using Base::operator*;
766 
768  Map(Scalar* coeffs)
769  : so2_(coeffs),
770  translation_(coeffs + Sophus::SO2<Scalar>::num_parameters) {}
771 
774  SOPHUS_FUNC Map<Sophus::SO2<Scalar>, Options>& so2() { return so2_; }
775 
778  SOPHUS_FUNC Map<Sophus::SO2<Scalar>, Options> const& so2() const {
779  return so2_;
780  }
781 
784  SOPHUS_FUNC Map<Sophus::Vector2<Scalar>, Options>& translation() {
785  return translation_;
786  }
787 
790  SOPHUS_FUNC Map<Sophus::Vector2<Scalar>, Options> const& translation() const {
791  return translation_;
792  }
793 
794  protected:
795  Map<Sophus::SO2<Scalar>, Options> so2_;
796  Map<Sophus::Vector2<Scalar>, Options> translation_;
797 };
798 
802 template <class Scalar_, int Options>
803 class Map<Sophus::SE2<Scalar_> const, Options>
804  : public Sophus::SE2Base<Map<Sophus::SE2<Scalar_> const, Options>> {
805  public:
807  using Scalar = Scalar_;
809  using Point = typename Base::Point;
811  using Tangent = typename Base::Tangent;
812  using Adjoint = typename Base::Adjoint;
813 
814  using Base::operator*=;
815  using Base::operator*;
816 
817  SOPHUS_FUNC Map(Scalar const* coeffs)
818  : so2_(coeffs),
819  translation_(coeffs + Sophus::SO2<Scalar>::num_parameters) {}
820 
823  SOPHUS_FUNC Map<Sophus::SO2<Scalar> const, Options> const& so2() const {
824  return so2_;
825  }
826 
829  SOPHUS_FUNC Map<Sophus::Vector2<Scalar> const, Options> const& translation()
830  const {
831  return translation_;
832  }
833 
834  protected:
835  Map<Sophus::SO2<Scalar> const, Options> const so2_;
836  Map<Sophus::Vector2<Scalar> const, Options> const translation_;
837 };
838 } // namespace Eigen
839 
840 #endif
Eigen::internal::traits< Sophus::SE2< Scalar_, Options > >::TranslationType
Sophus::Vector2< Scalar, Options > TranslationType
Definition: se2.hpp:22
Sophus::SE2Base::operator=
SOPHUS_FUNC SE2Base< Derived > & operator=(SE2Base< OtherDerived > const &other)
Definition: se2.hpp:224
c1
const Scalar c1
Definition: Se2_Dx_exp_x.cpp:2
Sophus::SO2::Transformation
typename Base::Transformation Transformation
Definition: so2.hpp:341
Sophus::SE2::DoF
static constexpr int DoF
Definition: se2.hpp:368
Sophus::SO2< Scalar, Options >
Eigen
Definition: rxso2.hpp:16
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::Tangent
Vector< Scalar, DoF > Tangent
Definition: se2.hpp:77
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::so2_
Map< Sophus::SO2< Scalar >, Options > so2_
Definition: se2.hpp:795
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::HomogeneousPointProduct
Vector3< ReturnScalar< HPointDerived > > HomogeneousPointProduct
Definition: se2.hpp:95
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::Point
Vector2< Scalar > Point
Definition: se2.hpp:74
Sophus::SE2::trans
static SOPHUS_FUNC SE2 trans(Vector2< Scalar > const &xy)
Definition: se2.hpp:684
Sophus::SE2Base::N
static constexpr int N
Group transformations are 3x3 matrices.
Definition: se2.hpp:72
Sophus::SE2::hat
static SOPHUS_FUNC Transformation hat(Tangent const &a)
Definition: se2.hpp:633
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::Tangent
typename Base::Tangent Tangent
Definition: se2.hpp:811
Sophus::SE2::Dx_exp_x_at_0
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x_at_0()
Definition: se2.hpp:531
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::translation
SOPHUS_FUNC Map< Sophus::Vector2< Scalar >, Options > const & translation() const
Definition: se2.hpp:790
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::so2
SOPHUS_FUNC Map< Sophus::SO2< Scalar > const, Options > const & so2() const
Definition: se2.hpp:823
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::Tangent
typename Base::Tangent Tangent
Definition: se2.hpp:757
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::Scalar
Scalar_ Scalar
Definition: se2.hpp:807
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::SO2Type
typename Eigen::internal::traits< Map< Sophus::SE2< Scalar_ >, Options > >::SO2Type SO2Type
Definition: se2.hpp:63
Sophus::Vector3
Vector< Scalar, 3, Options > Vector3
Definition: types.hpp:21
Sophus::SE2Base
Definition: se2.hpp:58
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::Point
typename Base::Point Point
Definition: se2.hpp:755
Sophus::SO2::exp
static SOPHUS_FUNC SO2< Scalar > exp(Tangent const &theta)
Definition: so2.hpp:421
Sophus::SE2Base::translation
SOPHUS_FUNC TranslationType const & translation() const
Definition: se2.hpp:350
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::Map
SOPHUS_FUNC Map(Scalar const *coeffs)
Definition: se2.hpp:817
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::TranslationType
typename Eigen::internal::traits< Map< Sophus::SE2< Scalar_ >, Options > >::TranslationType TranslationType
Definition: se2.hpp:62
Sophus::SE2Base::so2
SOPHUS_FUNC SO2Type const & so2() const
Definition: se2.hpp:336
Sophus::SE2Base::operator*
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator*(Eigen::MatrixBase< HPointDerived > const &p) const
Definition: se2.hpp:260
Sophus::enable_if_t
typename std::enable_if< B, T >::type enable_if_t
Definition: common.hpp:221
Sophus::SE2Base::log
SOPHUS_FUNC Tangent log() const
Definition: se2.hpp:160
Sophus::SE2Base::matrix2x3
SOPHUS_FUNC Matrix< Scalar, 2, 3 > matrix2x3() const
Definition: se2.hpp:210
SOPHUS_ENSURE
#define SOPHUS_ENSURE(expr,...)
Definition: common.hpp:137
Sophus::SE2Base::Dx_this_mul_exp_x_at_0
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0() const
Definition: se2.hpp:123
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::HomogeneousPoint
typename Base::HomogeneousPoint HomogeneousPoint
Definition: se2.hpp:756
Sophus::SE2Base::operator*
SOPHUS_FUNC SE2Product< OtherDerived > operator*(SE2Base< OtherDerived > const &other) const
Definition: se2.hpp:233
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::HomogeneousPoint
typename Base::HomogeneousPoint HomogeneousPoint
Definition: se2.hpp:810
Sophus::Vector2
Vector< Scalar, 2, Options > Vector2
Definition: types.hpp:16
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::translation
SOPHUS_FUNC Map< Sophus::Vector2< Scalar > const, Options > const & translation() const
Definition: se2.hpp:829
Sophus::SE2Base::setRotationMatrix
SOPHUS_FUNC void setRotationMatrix(Matrix< Scalar, 2, 2 > const &R)
Definition: se2.hpp:319
c7
const Scalar c7
Definition: Se2_Dx_exp_x.cpp:8
Sophus::SE2::so2
SOPHUS_FUNC SO2Member & so2()
Definition: se2.hpp:460
Sophus::SE2::num_parameters
static constexpr int num_parameters
Definition: se2.hpp:369
Sophus::SO2Base
Definition: so2.hpp:77
Sophus::SE2Base::translation
SOPHUS_FUNC TranslationType & translation()
Definition: se2.hpp:343
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::Adjoint
typename Base::Adjoint Adjoint
Definition: se2.hpp:758
Sophus::SE2::translation
SOPHUS_FUNC TranslationMember const & translation() const
Definition: se2.hpp:472
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::so2
SOPHUS_FUNC Map< Sophus::SO2< Scalar >, Options > const & so2() const
Definition: se2.hpp:778
Sophus::SE2::Dxi_exp_x_matrix_at_0
static SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0(int i)
Definition: se2.hpp:544
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::Adjoint
Matrix< Scalar, DoF, DoF > Adjoint
Definition: se2.hpp:78
Sophus::SE2::SE2
SOPHUS_FUNC SE2(typename SO2< Scalar >::Transformation const &rotation_matrix, Point const &translation)
Definition: se2.hpp:417
Sophus::SE2Base::params
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params() const
Definition: se2.hpp:295
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::ReturnScalar
typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType ReturnScalar
Definition: se2.hpp:86
Sophus::SE2::lieBracket
static SOPHUS_FUNC Tangent lieBracket(Tangent const &a, Tangent const &b)
Definition: se2.hpp:650
Sophus::SE2::vee
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
Definition: se2.hpp:713
Sophus::SE2Base::cast
SOPHUS_FUNC SE2< NewScalarType > cast() const
Definition: se2.hpp:116
Sophus::SE2Base::operator*
SOPHUS_FUNC PointProduct< PointDerived > operator*(Eigen::MatrixBase< PointDerived > const &p) const
Definition: se2.hpp:250
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::Transformation
typename Base::Transformation Transformation
Definition: se2.hpp:808
Sophus::Matrix
Eigen::Matrix< Scalar, M, N > Matrix
Definition: types.hpp:41
Sophus
Definition: average.hpp:17
SOPHUS_FUNC
#define SOPHUS_FUNC
Definition: common.hpp:37
Sophus::SE2::SE2
SOPHUS_FUNC SE2(Transformation const &T)
Definition: se2.hpp:437
c2
const Scalar c2
Definition: Se2_Dx_exp_x.cpp:3
Sophus::SE2::Tangent
typename Base::Tangent Tangent
Definition: se2.hpp:375
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::Line
ParametrizedLine2< Scalar > Line
Definition: se2.hpp:76
Sophus::isOrthogonal
SOPHUS_FUNC bool isOrthogonal(Eigen::MatrixBase< D > const &R)
Definition: rotation_matrix.hpp:17
Sophus::SE2::TranslationMember
Vector2< Scalar, Options > TranslationMember
Definition: se2.hpp:378
Sophus::SE2
SE2 using default storage; derived from SE2Base.
Definition: se2.hpp:11
Sophus::SE2::exp
static SOPHUS_FUNC SE2< Scalar > exp(Tangent const &a)
Definition: se2.hpp:560
Sophus::SE2::SE2
SOPHUS_FUNC SE2(SO2Base< OtherDerived > const &so2, Eigen::MatrixBase< D > const &translation)
Definition: se2.hpp:402
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::PointProduct
Vector2< ReturnScalar< PointDerived > > PointProduct
Definition: se2.hpp:92
Sophus::SE2Base::inverse
SOPHUS_FUNC SE2< Scalar > inverse() const
Definition: se2.hpp:145
Sophus::SE2Base::setComplex
SOPHUS_FUNC void setComplex(Sophus::Vector2< Scalar > const &complex)
Definition: se2.hpp:311
Eigen::internal::traits< Map< Sophus::SE2< Scalar_ > const, Options > >::TranslationType
Map< Sophus::Vector2< Scalar > const, Options > TranslationType
Definition: se2.hpp:38
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::so2_
const Map< Sophus::SO2< Scalar > const, Options > so2_
Definition: se2.hpp:835
Sophus::SE2::transY
static SOPHUS_FUNC SE2 transY(Scalar const &y)
Definition: se2.hpp:696
c9
const Scalar c9
Definition: Se2_Dx_exp_x.cpp:10
Sophus::SE2Base::Adj
SOPHUS_FUNC Adjoint Adj() const
Definition: se2.hpp:103
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::Point
typename Base::Point Point
Definition: se2.hpp:809
Sophus::SE2::data
SOPHUS_FUNC Scalar const * data() const
Definition: se2.hpp:453
Sophus::SE2::data
SOPHUS_FUNC Scalar * data()
Definition: se2.hpp:446
c3
const Scalar c3
Definition: Se2_Dx_exp_x.cpp:4
Sophus::SE2Base::so2
SOPHUS_FUNC SO2Type & so2()
Definition: se2.hpp:331
Sophus::SE2::rot
static SOPHUS_FUNC SE2 rot(Scalar const &x)
Definition: se2.hpp:662
Sophus::SE2::Point
typename Base::Point Point
Definition: se2.hpp:373
Sophus::SE2Base::operator*
SOPHUS_FUNC Line operator*(Line const &l) const
Definition: se2.hpp:275
Sophus::SE2Base::operator=
SOPHUS_FUNC SE2Base & operator=(SE2Base const &other)=default
Sophus::SO2::hat
static SOPHUS_FUNC Transformation hat(Tangent const &theta)
Definition: so2.hpp:471
Sophus::SE2::HomogeneousPoint
typename Base::HomogeneousPoint HomogeneousPoint
Definition: se2.hpp:374
Sophus::SE2::Adjoint
typename Base::Adjoint Adjoint
Definition: se2.hpp:376
Sophus::IsFixedSizeVector
Definition: types.hpp:225
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::translation_
Map< Sophus::Vector2< Scalar >, Options > translation_
Definition: se2.hpp:796
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::translation_
const Map< Sophus::Vector2< Scalar > const, Options > translation_
Definition: se2.hpp:836
Sophus::Constants
Definition: common.hpp:146
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::Transformation
Matrix< Scalar, N, N > Transformation
Definition: se2.hpp:73
Sophus::Matrix3
Matrix< Scalar, 3, 3 > Matrix3
Definition: types.hpp:49
Sophus::SE2Base::operator*=
SOPHUS_FUNC SE2Base< Derived > & operator*=(SE2Base< OtherDerived > const &other)
Definition: se2.hpp:285
Sophus::SE2::SE2
SOPHUS_FUNC SE2(Scalar const &theta, Point const &translation)
Definition: se2.hpp:423
Sophus::SE2::SE2
SOPHUS_FUNC SE2(Vector2< Scalar > const &complex, Point const &translation)
Definition: se2.hpp:429
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::Scalar
Scalar_ Scalar
Definition: se2.hpp:753
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::HomogeneousPoint
Vector3< Scalar > HomogeneousPoint
Definition: se2.hpp:75
Sophus::SE2Base::rotationMatrix
SOPHUS_FUNC Matrix< Scalar, 2, 2 > rotationMatrix() const
Definition: se2.hpp:303
Sophus::SE2::SE2
SOPHUS_FUNC SE2(SE2Base< OtherDerived > const &other)
Definition: se2.hpp:393
Sophus::SE2Base::normalize
SOPHUS_FUNC void normalize()
Definition: se2.hpp:188
Sophus::SE2Base::DoF
static constexpr int DoF
Definition: se2.hpp:67
Sophus::SE2::Scalar
Scalar_ Scalar
Definition: se2.hpp:371
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::so2
SOPHUS_FUNC Map< Sophus::SO2< Scalar >, Options > & so2()
Definition: se2.hpp:774
c6
const Scalar c6
Definition: Se2_Dx_exp_x.cpp:7
Sophus::SE2::translation
SOPHUS_FUNC TranslationMember & translation()
Definition: se2.hpp:468
Sophus::SE2Base::matrix
SOPHUS_FUNC Transformation matrix() const
Definition: se2.hpp:200
Sophus::SE2::fitToSE2
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE2 > fitToSE2(Matrix3< Scalar > const &T)
Definition: se2.hpp:587
Sophus::SE2::trans
static SOPHUS_FUNC SE2 trans(T0 const &x, T1 const &y)
Definition: se2.hpp:680
Sophus::Vector
Eigen::Matrix< Scalar, M, 1, Options > Vector
Definition: types.hpp:13
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::Map
SOPHUS_FUNC Map(Scalar *coeffs)
Definition: se2.hpp:768
Sophus::SE2::SE2
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SE2()
Definition: se2.hpp:729
Sophus::SE2::transX
static SOPHUS_FUNC SE2 transX(Scalar const &x)
Definition: se2.hpp:690
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::translation
SOPHUS_FUNC Map< Sophus::Vector2< Scalar >, Options > & translation()
Definition: se2.hpp:784
Eigen::internal::traits< Sophus::SE2< Scalar_, Options > >::Scalar
Scalar_ Scalar
Definition: se2.hpp:21
Sophus::SE2::so2
SOPHUS_FUNC SO2Member const & so2() const
Definition: se2.hpp:464
Sophus::SE2::Transformation
typename Base::Transformation Transformation
Definition: se2.hpp:372
c5
const Scalar c5
Definition: Se2_Dx_exp_x.cpp:6
Sophus::ParametrizedLine2
ParametrizedLine< Scalar, 2, Options > ParametrizedLine2
Definition: types.hpp:77
Eigen::Map< Sophus::SE2< Scalar_ >, Options >::Transformation
typename Base::Transformation Transformation
Definition: se2.hpp:754
Eigen::internal::traits< Map< Sophus::SE2< Scalar_ > const, Options > >::Scalar
Scalar_ Scalar
Definition: se2.hpp:37
Sophus::SE2::so2_
SO2Member so2_
Definition: se2.hpp:724
c4
const Scalar c4
Definition: Se2_Dx_exp_x.cpp:5
Sophus::SE2::translation_
TranslationMember translation_
Definition: se2.hpp:725
so2.hpp
Sophus::SO2::vee
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
Definition: so2.hpp:521
Sophus::SE2Base::num_parameters
static constexpr int num_parameters
Definition: se2.hpp:70
Sophus::SE2::generator
static SOPHUS_FUNC Transformation generator(int i)
Definition: se2.hpp:612
Eigen::internal::traits< Map< Sophus::SE2< Scalar_ > const, Options > >::SO2Type
Map< Sophus::SO2< Scalar > const, Options > SO2Type
Definition: se2.hpp:39
c0
const Scalar c0
Definition: Se2_Dx_exp_x.cpp:1
c8
const Scalar c8
Definition: Se2_Dx_exp_x.cpp:9
Sophus::SO2::unit_complex
SOPHUS_FUNC ComplexMember const & unit_complex() const
Definition: so2.hpp:408
Sophus::SE2Base< Map< Sophus::SE2< Scalar_ >, Options > >::Scalar
typename Eigen::internal::traits< Map< Sophus::SE2< Scalar_ >, Options > >::Scalar Scalar
Definition: se2.hpp:60
Sophus::SE2::Dx_exp_x
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x(Tangent const &upsilon_theta)
Definition: se2.hpp:478
Sophus::SE2::sampleUniform
static SE2 sampleUniform(UniformRandomBitGenerator &generator)
Definition: se2.hpp:671
Eigen::Map< Sophus::SE2< Scalar_ > const, Options >::Adjoint
typename Base::Adjoint Adjoint
Definition: se2.hpp:812
Sophus::SE2Base::unit_complex
SOPHUS_FUNC Eigen::internal::traits< Derived >::SO2Type::ComplexT const & unit_complex() const
Definition: se2.hpp:358


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