42 : Base(model, key1, key2), accel_(accel), gyro_(gyro), dt_(dt) {
43 assert(model->dim() == 9);
49 : Base(model, key1, key2), accel_(imu.
head(3)), gyro_(imu.
tail(3)), dt_(dt) {
50 assert(imu.size() == 6);
51 assert(model->dim() == 9);
63 const This*
const f =
dynamic_cast<const This*
>(&
e);
71 std::string
a =
"FullIMUFactor: " +
s;
75 std::cout <<
"dt: " << dt_ << std::endl;
81 Vector6
z()
const {
return (
Vector(6) << accel_, gyro_).finished(); }
90 z.head(3).operator=(
accel_);
91 z.segment(3, 3).operator=(
gyro_);
92 z.tail(3).operator=(x2.
t());
93 if (H1) *H1 = numericalDerivative21<Vector9, PoseRTV, PoseRTV>(
95 if (H2) *H2 = numericalDerivative22<Vector9, PoseRTV, PoseRTV>(
104 return Vector6::Zero();
void print(const Matrix &A, const string &s, ostream &stream)
gtsam::NonlinearFactor::shared_ptr clone() const override
bool equals(const NonlinearFactor &e, double tol=1e-9) const override
noiseModel::Diagonal::shared_ptr model
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
~FullIMUFactor() override
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type tail(NType n)
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
FullIMUFactor< POSE > This
static const KeyFormatter DefaultKeyFormatter
virtual Vector evaluateError(const Pose3 &x1, const Pose3 &x2, OptionalMatrixType H1, OptionalMatrixType H2) const
const KeyFormatter & formatter
const Vector3 & gyro() const
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
NoiseModelFactorN< POSE, POSE > Base
Matrix * OptionalMatrixType
const Vector3 & accel() const
void print(const std::string &s="", const gtsam::KeyFormatter &formatter=gtsam::DefaultKeyFormatter) const override
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector evaluateError(const PoseRTV &x1, const PoseRTV &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Pose3 with translational velocity.
Non-linear factor base classes.
static Vector9 predict_proxy(const PoseRTV &x1, const PoseRTV &x2, double dt)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
std::shared_ptr< This > shared_ptr
FullIMUFactor(const Vector6 &imu, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
Point3 translationIntegration(const Rot3 &r2, const Velocity3 &v2, double dt) const
FullIMUFactor(const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
Vector6 imuPrediction(const PoseRTV &x2, double dt) const
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel