27 using namespace gtsam;
30 0.31686, 0.51505, 0.79645,
32 0.41733, 0.67835, -0.60471);
55 double measurement_dt(0.1);
64 Vector measurement_acc(
Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
67 InertialNavFactor_GlobalVelocity<Pose3, Vector3, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho,
world_omega_earth, model);
69 Rot3 R1(0.487316618, 0.125253866, 0.86419557,
70 0.580273724, 0.693095498, -0.427669306,
71 -0.652537293, 0.709880342, 0.265075427);
75 Rot3 R2(0.473618898, 0.119523052, 0.872582019,
76 0.609241153, 0.67099888, -0.422594037,
77 -0.636011287, 0.731761397, 0.244979388);
85 values.
insert(PoseKey1, Pose1);
86 values.
insert(PoseKey2, Pose2);
87 values.
insert(VelKey1, Vel1);
88 values.
insert(VelKey2, Vel2);
89 values.
insert(BiasKey1, Bias1);
92 ordering.push_back(PoseKey1);
93 ordering.push_back(VelKey1);
94 ordering.push_back(BiasKey1);
95 ordering.push_back(PoseKey2);
96 ordering.push_back(VelKey2);
100 for(
size_t i = 0;
i < 100000; ++
i) {
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
gtsam::Pose3 predictionErrorPose(const Pose3 &p1, const Vector3 &v1, const imuBias::ConstantBias &b1, const Pose3 &p2, const Vector3 &v2, const InertialNavFactor_GlobalVelocity< Pose3, Vector3, imuBias::ConstantBias > &factor)
A non-templated config holding any types of Manifold-group elements.
Inertial navigation factor (velocity in the global frame)
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
static enum @843 ordering
Pose2_ Expmap(const Vector3_ &xi)
Some functions to compute numerical derivatives.
gtsam::Rot3 world_R_ECEF(0.31686, 0.51505, 0.79645, 0.85173,-0.52399, 0, 0.41733, 0.67835,-0.60471)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
void g(const string &key, int i)
static const Vector3 world_rho(0.0,-1.5724e-05, 0.0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
gtsam::Vector ECEF_omega_earth(Vector3(0.0, 0.0, 7.292115e-5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
static const Vector3 world_g(0.0, 0.0, 9.81)
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
gtsam::Vector3 predictionErrorVel(const Pose3 &p1, const Vector3 &v1, const imuBias::ConstantBias &b1, const Pose3 &p2, const Vector3 &v2, const InertialNavFactor_GlobalVelocity< Pose3, Vector3, imuBias::ConstantBias > &factor)
gtsam::Vector world_omega_earth(world_R_ECEF.matrix()*ECEF_omega_earth)
void tictoc_finishedIteration_()
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Vector evaluateError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none) const override
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Gaussian::shared_ptr SharedGaussian