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 
21 namespace gtsam {
22 
26 template<class X>
28 
29 public:
30  typedef ParticleFactor This;
31  typedef std::shared_ptr<This> shared_ptr;
32 
33 };
34 
39 template<class X>
41 
42 public:
43 
48 
55  State init(const Vector& x0, const SharedDiagonal& P0) {
56  return std::make_shared<ParticleFactor<X> >();
57  }
58 
59 };
60 // ParticleFilter
61 
62 }// namespace gtsam
63 
66 #include <gtsam/geometry/Pose2.h>
68 
69 using namespace std;
70 using namespace gtsam;
71 
72 //******************************************************************************
73 
74 TEST( particleFactor, constructor ) {
75 // ParticleFactor<Pose2> pf;
76  //CHECK(assert_equal(expected, actual));
77 }
78 
79 //******************************************************************************
80 // Tests to do:
81 // Take two variables pf-x-*-y, eliminate x, multiply and sample then marginalize
82 TEST( particleFactor, eliminate) {
83 // ParticleFactor<Pose2> fx;
85 
86 }
87 
88 //******************************************************************************
89 
91 struct State: Vector {
92  State(double x, double y) :
93  Vector((Vector(2) << x, y).finished()) {
94  }
95 };
96 
97 //******************************************************************************
99 
100 // Create a Kalman filter of dimension 2
102 
103 // Create inital mean/covariance
104  State x_initial(0.0, 0.0);
106 
107 // Get initial state by passing initial mean/covariance to the filter
108  ParticleFilter<Pose2>::State p1 = pf1.init(x_initial, P1);
109 
110 // // Assert it has the correct mean, covariance and information
111 // EXPECT(assert_equal(x_initial, p1->mean()));
112 // Matrix Sigma = (Mat(2, 2) << 0.01, 0.0, 0.0, 0.01);
113 // EXPECT(assert_equal(Sigma, p1->covariance()));
114 // EXPECT(assert_equal(inverse(Sigma), p1->information()));
115 //
116 // // Create one with a sharedGaussian
117 // KalmanFilter::State p2 = pf1.init(x_initial, Sigma);
118 // EXPECT(assert_equal(Sigma, p2->covariance()));
119 //
120 // // Now make sure both agree
121 // EXPECT(assert_equal(p1->covariance(), p2->covariance()));
122 }
123 
124 //******************************************************************************
125 TEST( ParticleFilter, linear1 ) {
126 
127  // Create the controls and measurement properties for our example
128  Matrix F = I_2x2;
129  Matrix B = I_2x2;
130  Vector u = Vector2(1.0, 0.0);
132  Matrix Q = 0.01 * I_2x2;
133  Matrix H = I_2x2;
134  State z1(1.0, 0.0);
135  State z2(2.0, 0.0);
136  State z3(3.0, 0.0);
138  Matrix R = 0.01 * I_2x2;
139 
140 // Create the set of expected output TestValues
141  State expected0(0.0, 0.0);
142  Matrix P00 = 0.01 * I_2x2;
143 
144  State expected1(1.0, 0.0);
145  Matrix P01 = P00 + Q;
146  Matrix I11 = P01.inverse() + R.inverse();
147 
148  State expected2(2.0, 0.0);
149  Matrix P12 = I11.inverse() + Q;
150  Matrix I22 = P12.inverse() + R.inverse();
151 
152  State expected3(3.0, 0.0);
153  Matrix P23 = I22.inverse() + Q;
154  Matrix I33 = P23.inverse() + R.inverse();
155 
156 // Create a Kalman filter of dimension 2
157  KalmanFilter kf(2);
158 
159 // Create the Kalman Filter initialization point
160  State x_initial(0.0, 0.0);
161  SharedDiagonal P_initial = noiseModel::Isotropic::Sigma(2, 0.1);
162 
163 // Create initial KalmanFilter object
164  KalmanFilter::State p0 = kf.init(x_initial, P_initial);
165  EXPECT(assert_equal(expected0, p0->mean()));
166  EXPECT(assert_equal(P00, p0->covariance()));
167 
168 // Run iteration 1
169  KalmanFilter::State p1p = kf.predict(p0, F, B, u, modelQ);
170  EXPECT(assert_equal(expected1, p1p->mean()));
171  EXPECT(assert_equal(P01, p1p->covariance()));
172 
173  KalmanFilter::State p1 = kf.update(p1p, H, z1, modelR);
174  EXPECT(assert_equal(expected1, p1->mean()));
175  EXPECT(assert_equal(I11, p1->information()));
176 
177 // Run iteration 2 (with full covariance)
178  KalmanFilter::State p2p = kf.predictQ(p1, F, B, u, Q);
179  EXPECT(assert_equal(expected2, p2p->mean()));
180 
181  KalmanFilter::State p2 = kf.update(p2p, H, z2, modelR);
182  EXPECT(assert_equal(expected2, p2->mean()));
183 
184 // Run iteration 3
185  KalmanFilter::State p3p = kf.predict(p2, F, B, u, modelQ);
186  EXPECT(assert_equal(expected3, p3p->mean()));
187  LONGS_EQUAL(3, (long)KalmanFilter::step(p3p));
188 
189  KalmanFilter::State p3 = kf.update(p3p, H, z3, modelR);
190  EXPECT(assert_equal(expected3, p3->mean()));
191  LONGS_EQUAL(3, (long)KalmanFilter::step(p3));
192 }
193 
194 //******************************************************************************
195 int main() {
196  TestResult tr;
197  return TestRegistry::runAllTests(tr);
198 }
199 //******************************************************************************
200 
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
Quaternion Q
Scalar * y
Key F(std::uint64_t j)
static Point3 p3
static const Unit3 z2
State predictQ(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const Matrix &Q) const
static int runAllTests(TestResult &result)
Vector3f p1
GaussianDensity::shared_ptr State
Definition: KalmanFilter.h:56
std::shared_ptr< This > shared_ptr
shared_ptr to this class
State predict(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const SharedDiagonal &modelQ) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Rot2 R(Rot2::fromAngle(0.1))
State(double x, double y)
Definition: BFloat16.h:88
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
static const Unit3 z3
Eigen::VectorXd Vector
Definition: Vector.h:38
State update(const State &p, const Matrix &H, const Vector &z, const SharedDiagonal &model) const
ParticleFactor< X >::shared_ptr State
#define EXPECT(condition)
Definition: Test.h:150
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
int main()
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
traits
Definition: chartTesting.h:28
static Symbol x0('x', 0)
Simple linear Kalman filter. Implemented using factor graphs, i.e., does Cholesky-based SRIF...
State init(const Vector &x0, const SharedDiagonal &P0) const
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)
static Point3 p2
const Point3 P0(0, 0, 0)
TEST(SmartFactorBase, Pinhole)
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
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:54