testRot2.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 
18 #include <gtsam/geometry/Rot2.h>
19 #include <gtsam/base/Testable.h>
20 #include <gtsam/base/testLie.h>
22 
23 using namespace gtsam;
24 
27 
28 Rot2 R(Rot2::fromAngle(0.1));
29 Point2 P(0.2, 0.7);
30 
31 /* ************************************************************************* */
32 TEST( Rot2, constructors_and_angle)
33 {
34  double c=cos(0.1), s=sin(0.1);
35  DOUBLES_EQUAL(0.1,R.theta(),1e-9);
36  CHECK(assert_equal(R,Rot2(0.1)));
40 }
41 
42 /* ************************************************************************* */
43 TEST( Rot2, unit)
44 {
45  EXPECT(assert_equal(Point2(1.0, 0.0), Rot2::fromAngle(0).unit()));
46  EXPECT(assert_equal(Point2(0.0, 1.0), Rot2::fromAngle(M_PI/2.0).unit()));
47 }
48 
49 /* ************************************************************************* */
50 TEST( Rot2, transpose)
51 {
53  Matrix actual = R.transpose();
54  CHECK(assert_equal(expected,actual));
55 }
56 
57 /* ************************************************************************* */
59 {
62 
63  Matrix H1, H2;
64  (void) Rot2::fromAngle(1.0).compose(Rot2::fromAngle(2.0), H1, H2);
65  EXPECT(assert_equal(I_1x1, H1));
66  EXPECT(assert_equal(I_1x1, H2));
67 }
68 
69 /* ************************************************************************* */
71 {
74 
75  Matrix H1, H2;
76  (void) Rot2::fromAngle(1.0).between(Rot2::fromAngle(2.0), H1, H2);
77  EXPECT(assert_equal(-I_1x1, H1));
78  EXPECT(assert_equal(I_1x1, H2));
79 }
80 
81 /* ************************************************************************* */
83 {
84  CHECK(R.equals(R));
85  Rot2 zero;
86  CHECK(!R.equals(zero));
87 }
88 
89 /* ************************************************************************* */
90 TEST( Rot2, expmap)
91 {
92  Vector v = Z_1x1;
94 }
95 
96 /* ************************************************************************* */
98 {
99  Rot2 rot0(Rot2::fromAngle(M_PI/2.0));
101  Vector expected = (Vector(1) << M_PI/2.0).finished();
102  Vector actual = rot0.localCoordinates(rot);
103  CHECK(assert_equal(expected, actual));
104 }
105 
106 /* ************************************************************************* */
107 // rotate and derivatives
108 inline Point2 rotate_(const Rot2 & R, const Point2& p) {return R.rotate(p);}
110 {
111  Matrix H1, H2;
112  Point2 actual = R.rotate(P, H1, H2);
113  CHECK(assert_equal(actual,R*P));
114  Matrix numerical1 = numericalDerivative21(rotate_, R, P);
115  CHECK(assert_equal(numerical1,H1));
116  Matrix numerical2 = numericalDerivative22(rotate_, R, P);
117  CHECK(assert_equal(numerical2,H2));
118 }
119 
120 /* ************************************************************************* */
121 // unrotate and derivatives
122 inline Point2 unrotate_(const Rot2& R, const Point2& p) {return R.unrotate(p);}
124 {
125  Matrix H1, H2;
126  Point2 w = R * P, actual = R.unrotate(w, H1, H2);
127  CHECK(assert_equal(actual,P));
128  Matrix numerical1 = numericalDerivative21(unrotate_, R, w);
129  CHECK(assert_equal(numerical1,H1));
130  Matrix numerical2 = numericalDerivative22(unrotate_, R, w);
131  CHECK(assert_equal(numerical2,H2));
132 }
133 
134 /* ************************************************************************* */
136 TEST( Rot2, relativeBearing )
137 {
138  Point2 l1(1, 0), l2(1, 1);
139  Matrix expectedH, actualH;
140 
141  // establish relativeBearing is indeed zero
142  Rot2 actual1 = Rot2::relativeBearing(l1, actualH);
143  CHECK(assert_equal(Rot2(),actual1));
144 
145  // Check numerical derivative
147  CHECK(assert_equal(expectedH,actualH));
148 
149  // establish relativeBearing is indeed 45 degrees
150  Rot2 actual2 = Rot2::relativeBearing(l2, actualH);
151  CHECK(assert_equal(Rot2::fromAngle(M_PI/4.0),actual2));
152 
153  // Check numerical derivative
155  CHECK(assert_equal(expectedH,actualH));
156 }
157 
158 //******************************************************************************
159 namespace {
160 Rot2 id;
161 Rot2 T1(0.1);
162 Rot2 T2(0.2);
163 } // namespace
164 
165 //******************************************************************************
166 TEST(Rot2, Invariants) {
167  EXPECT(check_group_invariants(id, id));
168  EXPECT(check_group_invariants(id, T1));
169  EXPECT(check_group_invariants(T2, id));
170  EXPECT(check_group_invariants(T2, T1));
171 
172  EXPECT(check_manifold_invariants(id, id));
173  EXPECT(check_manifold_invariants(id, T1));
174  EXPECT(check_manifold_invariants(T2, id));
175  EXPECT(check_manifold_invariants(T2, T1));
176 }
177 
178 //******************************************************************************
179 TEST(Rot2, LieGroupDerivatives) {
184 }
185 
186 //******************************************************************************
187 TEST(Rot2, ChartDerivatives) {
188  CHECK_CHART_DERIVATIVES(id, id);
192 }
193 
194 /* ************************************************************************* */
195 int main() {
196  TestResult tr;
197  return TestRegistry::runAllTests(tr);
198 }
199 /* ************************************************************************* */
200 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
gtsam::logmap
gtsam::Expression< typename gtsam::traits< T >::TangentVector > logmap(const gtsam::Expression< T > &x1, const gtsam::Expression< T > &x2)
logmap
Definition: slam/expressions.h:192
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Rot2::unrotate
Point2 unrotate(const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const
Definition: Rot2.cpp:110
GTSAM_CONCEPT_TESTABLE_INST
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176
Testable.h
Concept check for values that can be used in unit tests.
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
l2
gtsam::Key l2
Definition: testLinearContainerFactor.cpp:24
TestHarness.h
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::Rot2::fromCosSin
static Rot2 fromCosSin(double c, double s)
Named constructor from cos(theta),sin(theta) pair.
Definition: Rot2.cpp:27
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
gtsam::numericalDerivative11
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition: numericalDerivative.h:110
gtsam::Rot2::relativeBearing
static Rot2 relativeBearing(const Point2 &d, OptionalJacobian< 1, 2 > H={})
Definition: Rot2.cpp:119
gtsam::Rot2::atan2
static Rot2 atan2(double y, double x)
Definition: Rot2.cpp:33
gtsam::Rot2::theta
double theta() const
Definition: Rot2.h:186
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
pt
static const Point3 pt(1.0, 2.0, 3.0)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Rot2::matrix
Matrix2 matrix() const
Definition: Rot2.cpp:85
testLie.h
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
rot
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
Definition: level1_real_impl.h:79
Rot2.h
2D rotation
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
gtsam::compose
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:23
gtsam::Rot2::fromAngle
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
Definition: Rot2.h:61
id
static const Similarity3 id
Definition: testSimilarity3.cpp:44
gtsam::unrotate
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
Definition: slam/expressions.h:109
gtsam::rotate
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
Definition: slam/expressions.h:97
gtsam::Rot2::equals
bool equals(const Rot2 &R, double tol=1e-9) const
Definition: Rot2.cpp:51
DOUBLES_EQUAL
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
GTSAM_CONCEPT_LIE_INST
#define GTSAM_CONCEPT_LIE_INST(T)
Definition: Lie.h:372
main
int main()
Definition: testRot2.cpp:195
zero
EIGEN_DONT_INLINE Scalar zero()
Definition: svd_common.h:296
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
CHECK_LIE_GROUP_DERIVATIVES
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
unrotate_
Point2 unrotate_(const Rot2 &R, const Point2 &p)
Definition: testRot2.cpp:122
gtsam::Rot2::transpose
Matrix2 transpose() const
Definition: Rot2.cpp:92
gtsam::LieGroup::localCoordinates
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
gtsam::equals
Definition: Testable.h:112
TestResult
Definition: TestResult.h:26
gtsam::Rot2::rotate
Point2 rotate(const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const
Definition: Rot2.cpp:100
gtsam::Rot2
Definition: Rot2.h:35
gtsam
traits
Definition: SFMdata.h:40
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
l1
gtsam::Key l1
Definition: testLinearContainerFactor.cpp:24
p
float * p
Definition: Tutorial_Map_using.cpp:9
relativeBearing_
Rot2 relativeBearing_(const Point2 &pt)
Definition: testRot2.cpp:135
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::LieGroup::retract
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
M_PI
#define M_PI
Definition: mconf.h:117
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::Rot2::inverse
Rot2 inverse() const
Definition: Rot2.h:113
CHECK_CHART_DERIVATIVES
#define CHECK_CHART_DERIVATIVES(t1, t2)
Definition: testLie.h:85
P
Point2 P(0.2, 0.7)
R
Rot2 R(Rot2::fromAngle(0.1))
rotate_
Point2 rotate_(const Rot2 &R, const Point2 &p)
Definition: testRot2.cpp:108


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:23