Updated timing scripts for comma initializer
parent
aa093a35da
commit
77254900f2
|
@ -31,7 +31,7 @@ gtsam::Rot3 world_R_ECEF(
|
|||
0.85173, -0.52399, 0,
|
||||
0.41733, 0.67835, -0.60471);
|
||||
|
||||
gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5));
|
||||
gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5).finished());
|
||||
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -54,8 +54,8 @@ int main() {
|
|||
|
||||
double measurement_dt(0.1);
|
||||
Vector world_g((Vector(3) << 0.0, 0.0, 9.81).finished());
|
||||
Vector world_rho((Vector(3) << 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5));
|
||||
Vector world_rho((Vector(3) << 0.0, -1.5724e-05, 0.0).finished()); // NED system
|
||||
gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5).finished());
|
||||
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
|
||||
SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
|
|
|
@ -63,7 +63,7 @@ int main()
|
|||
+0.,-5.,
|
||||
10., 0.,
|
||||
+0.,10.
|
||||
);
|
||||
).finished();
|
||||
|
||||
Matrix Al1 = (Matrix(8, 10) <<
|
||||
// l1
|
||||
|
@ -75,7 +75,7 @@ int main()
|
|||
0., 5.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||
0., 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||
0., 0.,1.,2.,3.,4.,5.,6.,7.,8.
|
||||
);
|
||||
).finished();
|
||||
|
||||
Matrix Ax1 = (Matrix(8, 2) <<
|
||||
// x1
|
||||
|
@ -87,7 +87,7 @@ int main()
|
|||
0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||
-10., 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||
0.00,-10.,1.,2.,3.,4.,5.,6.,7.,8.
|
||||
);
|
||||
).finished();
|
||||
|
||||
// and a RHS
|
||||
Vector b2(8);
|
||||
|
|
|
@ -36,14 +36,14 @@ int main(int argc, char *argv[]) {
|
|||
Values::shared_ptr solution;
|
||||
NonlinearFactorGraph::shared_ptr g;
|
||||
string inputFile = findExampleDataFile("w10000");
|
||||
SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0));
|
||||
SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished());
|
||||
boost::tie(g, solution) = load2D(inputFile, model);
|
||||
|
||||
// add noise to create initial estimate
|
||||
Values initial;
|
||||
Sampler sampler(42u);
|
||||
Values::ConstFiltered<Pose2> poses = solution->filter<Pose2>();
|
||||
SharedDiagonal noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0));
|
||||
SharedDiagonal noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0).finished());
|
||||
BOOST_FOREACH(const Values::ConstFiltered<Pose2>::KeyValuePair& it, poses)
|
||||
initial.insert(it.key, it.value.retract(sampler.sampleNewModel(noise)));
|
||||
|
||||
|
|
|
@ -61,7 +61,7 @@ Pose2 Pose2betweenOptimized(const Pose2& r1, const Pose2& r2,
|
|||
*H1 = (Matrix(3,3) <<
|
||||
-c, -s, dt1,
|
||||
s, -c, dt2,
|
||||
0.0, 0.0,-1.0);
|
||||
0.0, 0.0,-1.0).finished();
|
||||
}
|
||||
if (H2) *H2 = Matrix::Identity(3,3);
|
||||
|
||||
|
@ -138,7 +138,7 @@ int main()
|
|||
|
||||
// create a random pose:
|
||||
double x = 4.0, y = 2.0, r = 0.3;
|
||||
Vector v = (Vector(3) << x, y, r);
|
||||
Vector v = (Vector(3) << x, y, r).finished();
|
||||
Pose2 X = Pose2(3,2,0.4), X2 = X.retract(v), X3(5,6,0.3);
|
||||
|
||||
TEST(Expmap, Pose2::Expmap(v));
|
||||
|
|
|
@ -37,7 +37,7 @@ int main()
|
|||
|
||||
double norm=sqrt(1.0+16.0+4.0);
|
||||
double x=1.0/norm, y=4.0/norm, z=2.0/norm;
|
||||
Vector v = (Vector(6) << x, y, z, 0.1, 0.2, -0.1);
|
||||
Vector v = (Vector(6) << x, y, z, 0.1, 0.2, -0.1).finished();
|
||||
Pose3 T = Pose3::Expmap((Vector(6) << 0.1, 0.1, 0.2, 0.1, 0.4, 0.2).finished()), T2 = T.retract(v);
|
||||
Matrix H1,H2;
|
||||
|
||||
|
|
|
@ -95,7 +95,7 @@ int main()
|
|||
// create a random direction:
|
||||
double norm=sqrt(16.0+4.0);
|
||||
double x=4.0/norm, y=2.0/norm;
|
||||
Vector v = (Vector(2) << x, y);
|
||||
Vector v = (Vector(2) << x, y).finished();
|
||||
Rot2 R = Rot2(0.4), R2 = R.retract(v), R3(0.6);
|
||||
|
||||
TEST(Rot2_Expmap, Rot2::Expmap(v));
|
||||
|
|
|
@ -39,7 +39,7 @@ int main()
|
|||
// create a random direction:
|
||||
double norm=sqrt(1.0+16.0+4.0);
|
||||
double x=1.0/norm, y=4.0/norm, z=2.0/norm;
|
||||
Vector v = (Vector(3) << x, y, z);
|
||||
Vector v = (Vector(3) << x, y, z).finished();
|
||||
Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2), R2 = R.retract(v);
|
||||
|
||||
TEST("Rodriguez formula given axis angle", Rot3::rodriguez(v,0.001))
|
||||
|
|
Loading…
Reference in New Issue