testSlamExpressions.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/slam/expressions.h>
21 
23 
24 #include <iostream>
25 
26 using namespace std;
27 using namespace gtsam;
28 
29 /* ************************************************************************* */
30 TEST(SlamExpressions, project2) {
31  typedef Expression<CalibratedCamera> CalibratedCamera_;
32 
33  Rot3_ rot3_expr('r', 0); // unknown rotation !
34  Point3_ t_expr(Point3(1, 2, 3)); // known translation
35  Pose3_ pose_expr(&Pose3::Create, rot3_expr, t_expr);
36  CalibratedCamera_ camera_expr(&CalibratedCamera::Create, pose_expr);
37  Point3_ point3_expr('p', 12); // unknown 3D point with index 12, for funsies
38  Point2_ point2_expr = project2<CalibratedCamera>(camera_expr, point3_expr);
39 
40  // Set the linearization point
41  Values values;
42  values.insert(Symbol('r', 0), Rot3());
43  values.insert(Symbol('p', 12), Point3(4, 5, 6));
44 
45  EXPECT_CORRECT_EXPRESSION_JACOBIANS(point2_expr, values, 1e-7, 1e-5);
46 }
47 
48 /* ************************************************************************* */
49 TEST(SlamExpressions, rotation) {
50  Pose3_ T_(0);
51  const Rot3_ R_ = rotation(T_);
52 }
53 
54 /* ************************************************************************* */
55 TEST(SlamExpressions, unrotate) {
56  Rot3_ R_(0);
57  Point3_ p_(1);
58  const Point3_ q_ = unrotate(R_, p_);
59 }
60 
61 /* ************************************************************************* */
62 TEST(SlamExpressions, logmap) {
63  Pose3_ T1_(0);
64  Pose3_ T2_(1);
65  const Vector6_ l = logmap(T1_, T2_);
66 }
67 
68 /* ************************************************************************* */
69 int main() {
70  TestResult tr;
71  return TestRegistry::runAllTests(tr);
72 }
73 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::internal::rotation
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Definition: slam/expressions.h:80
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
TEST
TEST(SlamExpressions, project2)
Definition: testSlamExpressions.cpp:30
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
project2
static Point2 project2(const CalibratedCamera &camera, const Point3 &point)
Definition: testCalibratedCamera.cpp:127
TestHarness.h
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
main
int main()
Definition: testSlamExpressions.cpp:69
gtsam::Expression
Definition: Expression.h:47
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
l
static const Line3 l(Rot3(), 1, 1)
TestResult
Definition: TestResult.h:26
expressionTesting.h
Test harness methods for expressions.
gtsam
traits
Definition: chartTesting.h:28
leaf::values
leaf::MyValues values
gtsam::Values
Definition: Values.h:65
expressions.h
Common expressions for solving geometry/slam/sfm problems.
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::testing::unrotate
P unrotate(const T &r, const P &pt)
Definition: lieProxies.h:50
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
EXPECT_CORRECT_EXPRESSION_JACOBIANS
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
Definition: expressionTesting.h:48
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:06:53