testParticleFactor.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 
20 #include <boost/make_shared.hpp>
21 
22 namespace gtsam {
23 
27 template<class X>
29 
30 public:
31  typedef ParticleFactor This;
32  typedef boost::shared_ptr<This> shared_ptr;
33 
34 };
35 
40 template<class X>
42 
43 public:
44 
49 
56  State init(const Vector& x0, const SharedDiagonal& P0) {
57  return boost::make_shared<ParticleFactor<X> >();
58  }
59 
60 };
61 // ParticleFilter
62 
63 }// namespace gtsam
64 
67 #include <gtsam/geometry/Pose2.h>
69 
70 using namespace std;
71 using namespace gtsam;
72 
73 //******************************************************************************
74 
75 TEST( particleFactor, constructor ) {
76 // ParticleFactor<Pose2> pf;
77  //CHECK(assert_equal(expected, actual));
78 }
79 
80 //******************************************************************************
81 // Tests to do:
82 // Take two variables pf-x-*-y, eliminate x, multiply and sample then marginalize
83 TEST( particleFactor, eliminate) {
84 // ParticleFactor<Pose2> fx;
86 
87 }
88 
89 //******************************************************************************
90 
92 struct State: Vector {
93  State(double x, double y) :
94  Vector((Vector(2) << x, y).finished()) {
95  }
96 };
97 
98 //******************************************************************************
100 
101 // Create a Kalman filter of dimension 2
103 
104 // Create inital mean/covariance
105  State x_initial(0.0, 0.0);
107 
108 // Get initial state by passing initial mean/covariance to the filter
109  ParticleFilter<Pose2>::State p1 = pf1.init(x_initial, P1);
110 
111 // // Assert it has the correct mean, covariance and information
112 // EXPECT(assert_equal(x_initial, p1->mean()));
113 // Matrix Sigma = (Mat(2, 2) << 0.01, 0.0, 0.0, 0.01);
114 // EXPECT(assert_equal(Sigma, p1->covariance()));
115 // EXPECT(assert_equal(inverse(Sigma), p1->information()));
116 //
117 // // Create one with a sharedGaussian
118 // KalmanFilter::State p2 = pf1.init(x_initial, Sigma);
119 // EXPECT(assert_equal(Sigma, p2->covariance()));
120 //
121 // // Now make sure both agree
122 // EXPECT(assert_equal(p1->covariance(), p2->covariance()));
123 }
124 
125 //******************************************************************************
126 TEST( ParticleFilter, linear1 ) {
127 
128  // Create the controls and measurement properties for our example
129  Matrix F = I_2x2;
130  Matrix B = I_2x2;
131  Vector u = Vector2(1.0, 0.0);
133  Matrix Q = 0.01 * I_2x2;
134  Matrix H = I_2x2;
135  State z1(1.0, 0.0);
136  State z2(2.0, 0.0);
137  State z3(3.0, 0.0);
139  Matrix R = 0.01 * I_2x2;
140 
141 // Create the set of expected output TestValues
142  State expected0(0.0, 0.0);
143  Matrix P00 = 0.01 * I_2x2;
144 
145  State expected1(1.0, 0.0);
146  Matrix P01 = P00 + Q;
147  Matrix I11 = P01.inverse() + R.inverse();
148 
149  State expected2(2.0, 0.0);
150  Matrix P12 = I11.inverse() + Q;
151  Matrix I22 = P12.inverse() + R.inverse();
152 
153  State expected3(3.0, 0.0);
154  Matrix P23 = I22.inverse() + Q;
155  Matrix I33 = P23.inverse() + R.inverse();
156 
157 // Create a Kalman filter of dimension 2
158  KalmanFilter kf(2);
159 
160 // Create the Kalman Filter initialization point
161  State x_initial(0.0, 0.0);
162  SharedDiagonal P_initial = noiseModel::Isotropic::Sigma(2, 0.1);
163 
164 // Create initial KalmanFilter object
165  KalmanFilter::State p0 = kf.init(x_initial, P_initial);
166  EXPECT(assert_equal(expected0, p0->mean()));
167  EXPECT(assert_equal(P00, p0->covariance()));
168 
169 // Run iteration 1
170  KalmanFilter::State p1p = kf.predict(p0, F, B, u, modelQ);
171  EXPECT(assert_equal(expected1, p1p->mean()));
172  EXPECT(assert_equal(P01, p1p->covariance()));
173 
174  KalmanFilter::State p1 = kf.update(p1p, H, z1, modelR);
175  EXPECT(assert_equal(expected1, p1->mean()));
176  EXPECT(assert_equal(I11, p1->information()));
177 
178 // Run iteration 2 (with full covariance)
179  KalmanFilter::State p2p = kf.predictQ(p1, F, B, u, Q);
180  EXPECT(assert_equal(expected2, p2p->mean()));
181 
182  KalmanFilter::State p2 = kf.update(p2p, H, z2, modelR);
183  EXPECT(assert_equal(expected2, p2->mean()));
184 
185 // Run iteration 3
186  KalmanFilter::State p3p = kf.predict(p2, F, B, u, modelQ);
187  EXPECT(assert_equal(expected3, p3p->mean()));
188  LONGS_EQUAL(3, (long)KalmanFilter::step(p3p));
189 
190  KalmanFilter::State p3 = kf.update(p3p, H, z3, modelR);
191  EXPECT(assert_equal(expected3, p3->mean()));
192  LONGS_EQUAL(3, (long)KalmanFilter::step(p3));
193 }
194 
195 //******************************************************************************
196 int main() {
197  TestResult tr;
198  return TestRegistry::runAllTests(tr);
199 }
200 //******************************************************************************
201 
State predict(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const SharedDiagonal &modelQ) const
Quaternion Q
Scalar * y
static Point3 p3
static int runAllTests(TestResult &result)
Vector3f p1
State update(const State &p, const Matrix &H, const Vector &z, const SharedDiagonal &model) const
GaussianDensity::shared_ptr State
Definition: KalmanFilter.h:56
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
State(double x, double y)
Definition: Half.h:150
Vector3f p0
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
Point2 z2
State predictQ(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const Matrix &Q) const
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
Signature::Row F
Definition: Signature.cpp:53
static const Unit3 z3
Eigen::VectorXd Vector
Definition: Vector.h:38
ParticleFactor< X >::shared_ptr State
#define EXPECT(condition)
Definition: Test.h:151
int main()
State init(const Vector &x0, const SharedDiagonal &P0) const
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
static Symbol x0('x', 0)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Simple linear Kalman filter. Implemented using factor graphs, i.e., does Cholesky-based SRIF...
Point2 z1
Eigen::Vector2d Vector2
Definition: Vector.h:42
ParticleFactor This
Typedef to this class.
The quaternion class used to represent 3D orientations and rotations.
State init(const Vector &x0, const SharedDiagonal &P0)
TEST(LPInitSolver, InfiniteLoopSingleVar)
static Point3 p2
const Point3 P0(0, 0, 0)
2D Pose
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
static Key step(const State &p)
Definition: KalmanFilter.h:92
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:30