timeRot2.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/geometry/Pose2.h>
20 #include <gtsam/base/timing.h>
21 #include <iostream>
22 
23 using namespace std;
24 using namespace gtsam;
25 
26 /* ************************************************************************* */
27 #define TEST(TITLE,STATEMENT) \
28  gttic_(TITLE); \
29  for(int i = 0; i < n; i++) \
30  STATEMENT; \
31  gttoc_(TITLE);
32 
33 /* ************************************************************************* */
34 Rot2 Rot2betweenDefault(const Rot2& r1, const Rot2& r2) {
35  return r1.inverse() * r2;
36 }
37 
38 /* ************************************************************************* */
40  // Same as compose but sign of sin for r1 is reversed
41  return Rot2::fromCosSin(r1.c() * r2.c() + r1.s() * r2.s(), -r1.s() * r2.c() + r1.c() * r2.s());
42 }
43 
44 /* ************************************************************************* */
46  boost::optional<Matrix&> H1, boost::optional<Matrix&> H2)
47 {
48  Rot2 hx = p1.between(p2, H1, H2); // h(x)
49  // manifold equivalent of h(x)-z -> log(z,h(x))
50  return measured.localCoordinates(hx);
51 }
52 
53 /* ************************************************************************* */
55  boost::optional<Matrix&> H1, boost::optional<Matrix&> H2)
56 {
57  Rot2 hx = Rot2betweenOptimized(p1, p2); // h(x)
58  if (H1) *H1 = -I_1x1;
59  if (H2) *H2 = I_1x1;
60  // manifold equivalent of h(x)-z -> log(z,h(x))
61  return Rot2::Logmap(Rot2betweenOptimized(measured, hx));
62 }
63 
64 /* ************************************************************************* */
66  boost::optional<Matrix&> H1, boost::optional<Matrix&> H2)
67 {
68  // TODO: Implement
69  Rot2 hx = Rot2betweenOptimized(p1, p2); // h(x)
70  if (H1) *H1 = -I_1x1;
71  if (H2) *H2 = I_1x1;
72  // manifold equivalent of h(x)-z -> log(z,h(x))
73  return Rot2::Logmap(Rot2betweenOptimized(measured, hx));
74 }
75 
76 /* ************************************************************************* */
79  boost::optional<Matrix1&> H1, boost::optional<Matrix1&> H2)
80 {
81  // TODO: Implement
82  Rot2 hx = Rot2betweenOptimized(p1, p2); // h(x)
83  if (H1) *H1 = -Matrix1::Identity();
84  if (H2) *H2 = Matrix1::Identity();
85  // manifold equivalent of h(x)-z -> log(z,h(x))
86  return Rot2::Logmap(Rot2betweenOptimized(measured, hx));
87 }
88 
89 /* ************************************************************************* */
90 int main()
91 {
92  int n = 50000000;
93  cout << "NOTE: Times are reported for " << n << " calls" << endl;
94 
95  Vector1 v; v << 0.1;
96  Rot2 R = Rot2(0.4), R2(0.5), R3(0.6);
97 
98  TEST(Rot2_Expmap, Rot2::Expmap(v));
99  TEST(Rot2_Retract, R.retract(v));
100  TEST(Rot2_Logmap, Rot2::Logmap(R2));
101  TEST(Rot2_between, R.between(R2));
102  TEST(betweenDefault, Rot2betweenDefault(R, R2));
103  TEST(betweenOptimized, Rot2betweenOptimized(R, R2));
104  TEST(Rot2_localCoordinates, R.localCoordinates(R2));
105 
106  Matrix H1, H2;
107  Matrix1 H1f, H2f;
112 
113  // Print timings
114  tictoc_print_();
115 
116  return 0;
117 }
Rot2 Rot2betweenOptimized(const Rot2 &r1, const Rot2 &r2)
Definition: timeRot2.cpp:39
Vector3f p1
ArrayXcf v
Definition: Cwise_arg.cpp:1
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
Definition: Half.h:150
#define TEST(TITLE, STATEMENT)
Definition: timeRot2.cpp:27
Vector Rot2BetweenFactorEvaluateErrorOptimizedBetweenFixed(const Rot2 &measured, const Rot2 &p1, const Rot2 &p2, boost::optional< Matrix1 & > H1, boost::optional< Matrix1 & > H2)
Definition: timeRot2.cpp:78
Eigen::Matrix< double, 1, 1 > Matrix1
Definition: timeRot2.cpp:77
int main()
Definition: timeRot2.cpp:90
Eigen::VectorXd Vector
Definition: Vector.h:38
Vector Rot2BetweenFactorEvaluateErrorDefault(const Rot2 &measured, const Rot2 &p1, const Rot2 &p2, boost::optional< Matrix & > H1, boost::optional< Matrix & > H2)
Definition: timeRot2.cpp:45
void tictoc_print_()
Definition: timing.h:253
static const double r2
double s() const
Definition: Rot2.h:199
traits
Definition: chartTesting.h:28
static Rot3 R3
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
static const double r1
Vector Rot2BetweenFactorEvaluateErrorOptimizedBetween(const Rot2 &measured, const Rot2 &p1, const Rot2 &p2, boost::optional< Matrix & > H1, boost::optional< Matrix & > H2)
Definition: timeRot2.cpp:54
Class between(const Class &g) const
Definition: Lie.h:51
static Point3 p2
double c() const
Definition: Rot2.h:194
2D Pose
The matrix class, also used for vectors and row-vectors.
Point3 measured
Rot2 inverse() const
Definition: Rot2.h:110
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
Timing utilities.
Vector Rot2BetweenFactorEvaluateErrorOptimizedBetweenNoeye(const Rot2 &measured, const Rot2 &p1, const Rot2 &p2, boost::optional< Matrix & > H1, boost::optional< Matrix & > H2)
Definition: timeRot2.cpp:65
Rot2 Rot2betweenDefault(const Rot2 &r1, const Rot2 &r2)
Definition: timeRot2.cpp:34
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:135


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:38