testSimulated2DOriented.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 <tests/simulated2D.h>
21 #include <gtsam/inference/Symbol.h>
22 #include <gtsam/base/Testable.h>
24 
25 using namespace std;
26 using namespace gtsam;
27 
28 #include <iostream>
30 
31 // Convenience for named keys
34 
35 /* ************************************************************************* */
37 {
38  Pose2 x(1,-9, 0.1);
40  Matrix computed;
41  simulated2DOriented::prior(x,computed);
42  CHECK(assert_equal(numerical,computed,1e-9));
43 }
44 
45 /* ************************************************************************* */
47 {
48  Pose2 x1(1,-9,0.1),x2(-5,6,0.2);
49  Matrix H1,H2;
50  simulated2DOriented::odo(x1,x2,H1,H2);
52  CHECK(assert_equal(A1,H1,1e-9));
54  CHECK(assert_equal(A2,H2,1e-9));
55 }
56 
57 /* ************************************************************************* */
59 {
60  Pose2 measurement(0.2, 0.3, 0.1);
61  SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector3(1., 1., 1.));
62  simulated2DOriented::Odometry factor(measurement, model, X(1), X(2));
63 
65  config.insert(X(1), Pose2(1., 0., 0.2));
66  config.insert(X(2), Pose2(2., 0., 0.1));
67  std::shared_ptr<GaussianFactor> lf = factor.linearize(config);
68 }
69 
70 /* ************************************************************************* */
71 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
72 /* ************************************************************************* */
static Matrix A1
#define CHECK(condition)
Definition: Test.h:108
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
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.
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)
static Point2 measurement(323.0, 240.0)
Pose2 odo(const Pose2 &x1, const Pose2 &x2)
odometry between two poses
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
traits
Definition: chartTesting.h:28
measurement functions and derivatives for simulated 2D robot
TEST(simulated2DOriented, Dprior)
Pose3 x1
Definition: testPose3.cpp:663
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
void insert(Key j, const Value &val)
Definition: Values.cpp:155
#define X
Definition: icosphere.cpp:20
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Pose2 prior(const Pose2 &x)
Prior on a single pose.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:31