21 using namespace gtsam;
25 Point3 nM(22653.29982, -1956.83010, 44202.47862);
28 double scale = 255.0 / 50000.0;
40 Point3 dir3(nM.normalized());
41 Point2 dir2(nM.head(2).normalized());
54 Pose3 body_P3_sensor(Rot3::RzRyRx(
Vector3(1.5, 0.9, -1.15)),
81 ([&
f] (
const Pose2&
p) {
return f.evaluateError(p);},
94 ([&
f] (
const Pose3&
p) {
return f.evaluateError(p);},
105 const Rot2 nRs = n_R2_b * body_P2_sensor.rotation();
119 const Rot3 nRs = n_R3_b * body_P3_sensor.rotation();
Provides additional testing facilities for common data structures.
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
static int runAllTests(TestResult &result)
Bias bias2(biasAcc2, biasGyro2)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Implement functions needed for Testable.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Some functions to compute numerical derivatives.
Vector evaluateError(const POSE &nPb, OptionalMatrixType H) const override
Implement functions needed to derive from Factor.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Rot3 inverse() const
inverse of a rotation
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
TEST(MagPoseFactor, Constructors)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const SharedNoiseModel model3
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 scale
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
noiseModel::Base::shared_ptr SharedNoiseModel