26 using namespace gtsam;
39 Point2 x_initial(0.0, 0.0);
56 Point2 expected1(1.0, 0.0);
57 Point2 expected2(2.0, 0.0);
58 Point2 expected3(3.0, 0.0);
107 Base(noiseModel::
Diagonal::Sigmas(
Vector2(1.0, 1.0)), TestKey1, TestKey2), Q_(2,2) {
115 G << 1.0, 0.0, 0.0, 1.0;
116 w << 1.0, 0.0, 0.0, 1.0;
119 Q_ = w*w.transpose();
129 double x = x_t0.x() * x_t0.x();
130 double y = x_t0.x() * x_t0.y();
157 std::cout <<
s <<
": NonlinearMotionModel\n";
158 std::cout <<
" TestKey1: " << keyFormatter(
key1()) << std::endl;
159 std::cout <<
" TestKey2: " << keyFormatter(
key2()) << std::endl;
164 const This *
e =
dynamic_cast<const This*
> (&
f);
165 return (e !=
nullptr) && (
key1() == e->key1()) && (
key2() == e->key2());
174 return 0.5 * w.dot(w);
178 size_t dim()
const override {
184 return QInvSqrt(c.
at<
Point2>(
key1()))*unwhitenedError(c);
196 Vector b = -evaluateError(x1, x2, A1, A2);
199 if (constrained.get() !=
nullptr) {
201 A2, b, constrained));
204 Matrix Qinvsqrt = QInvSqrt(x1);
214 boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
215 boost::none)
const override {
226 *H2 = Matrix::Identity(
dim(),
dim());
229 return (p2 - prediction);
249 Base(noiseModel::Unit::Create(z.
size()), TestKey), z_(z), R_(1,1) {
266 z_hat(0) = 2*x_t1.x()*x_t1.x() - x_t1.x()*x_t1.y() - 2.5*x_t1.x() + 7*x_t1.y();
274 H(0,0) = 4*x_t1.x() - x_t1.y() - 2.5;
275 H(0,1) = -1*x_t1.x() + 7;
288 std::cout <<
s <<
": NonlinearMeasurementModel\n";
289 std::cout <<
" TestKey: " << keyFormatter(
key()) << std::endl;
294 const This *
e =
dynamic_cast<const This*
> (&
f);
295 return (e !=
nullptr) && Base::equals(f);
304 return 0.5 * w.dot(w);
308 size_t dim()
const override {
314 return RInvSqrt(c.
at<
Point2>(
key()))*unwhitenedError(c);
325 Vector b = -evaluateError(x1, A1);
328 if (constrained.get() !=
nullptr) {
332 Matrix Rinvsqrt = RInvSqrt(x1);
359 Point2 expected_predict[10];
360 Point2 expected_update[10];
361 expected_predict[0] =
Point2(0.81,0.99);
362 expected_update[0] =
Point2(0.824926197027,0.29509808);
363 expected_predict[1] =
Point2(0.680503230541,0.24343413);
364 expected_update[1] =
Point2(0.773360464065,0.43518355);
365 expected_predict[2] =
Point2(0.598086407378,0.33655375);
366 expected_update[2] =
Point2(0.908781566884,0.60766713);
367 expected_predict[3] =
Point2(0.825883936308,0.55223668);
368 expected_update[3] =
Point2(1.23221370495,0.74372849);
369 expected_predict[4] =
Point2(1.51835061468,0.91643243);
370 expected_update[4] =
Point2(1.32823362774,0.855855);
371 expected_predict[5] =
Point2(1.76420456986,1.1367754);
372 expected_update[5] =
Point2(1.36378040243,1.0623832);
373 expected_predict[6] =
Point2(1.85989698605,1.4488574);
374 expected_update[6] =
Point2(1.24068063304,1.3431964);
375 expected_predict[7] =
Point2(1.53928843321,1.6664778);
376 expected_update[7] =
Point2(1.04229257957,1.4856408);
377 expected_predict[8] =
Point2(1.08637382142,1.5484724);
378 expected_update[8] =
Point2(1.13201933157,1.5795507);
379 expected_predict[9] =
Point2(1.28146776705,1.7880819);
380 expected_update[9] =
Point2(1.22159588179,1.7434982);
396 Point2 x_initial(0.90, 1.10);
403 Point2 x_predict(0,0), x_update(0,0);
404 for(
unsigned int i = 0;
i < 10; ++
i){
407 x_predict = ekf.
predict(motionFactor);
411 x_update = ekf.
update(measurementFactor);
NoiseModelFactor2< Point2, Point2 > Base
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector h(const Point2 &x_t1) const
static int runAllTests(TestResult &result)
JacobiRotation< float > G
NonlinearMotionModel This
NonlinearMeasurementModel(const Symbol &TestKey, Vector z)
Rot2 R(Rot2::fromAngle(0.1))
NonlinearMeasurementModel()
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Matrix H(const Point2 &x_t1) const
NoiseModelFactor1< Point2 > Base
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 F(const Point2 &x_t0) const
static const KeyFormatter DefaultKeyFormatter
JacobianFactor factor3(keyY, A32, keyZ, A33, b3, noiseModel::Isotropic::Sigma(2, sigma3))
T update(const NoiseModelFactor &measurementFactor)
static shared_ptr Create(size_t dim)
Vector whitenedError(const Values &c) const
double error(const Values &c) const override
const Symbol key1('v', 1)
~NonlinearMotionModel() override
Class to perform generic Kalman Filtering using nonlinear factor graphs.
const ValueType at(Key j) const
size_t dim() const override
#define EXPECT(condition)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< GaussianFactor > linearize(const Values &c) const override
T predict(const NoiseModelFactor &motionFactor)
Vector evaluateError(const Point2 &p, boost::optional< Matrix & > H1=boost::none) const override
Matrix QInvSqrt(const Point2 &x_t0) const
double error(const Values &c) const override
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
~NonlinearMeasurementModel() override
Matrix inverse_square_root(const Matrix &A)
Non-linear factor base classes.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
The quaternion class used to represent 3D orientations and rotations.
const Symbol key2('v', 2)
NonlinearMeasurementModel This
NonlinearMotionModel(const Symbol &TestKey1, const Symbol &TestKey2)
TEST(LPInitSolver, InfiniteLoopSingleVar)
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
boost::shared_ptr< GaussianFactor > linearize(const Values &c) const override
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Vector whitenedError(const Values &c) const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector evaluateError(const Point2 &p1, const Point2 &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Matrix RInvSqrt(const Point2 &x_t0) const
Point2 f(const Point2 &x_t0) const
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
size_t dim() const override
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))