33 using namespace gtsam;
120 2, (
Matrix(2, 3) << 1, 0, 0, 0, 1, 0).finished(),
129 std::shared_ptr<GaussianFactor> gf = f.
linearize(values);
130 std::shared_ptr<JacobianFactor> jf =
142 if (H) *H << I_3x3, I_3x3, I_3x3;
148 if (H) *H = Matrix9::Identity();
179 typedef internal::BinaryExpression<Point2, Cal3_S2, Point2> Binary;
192 internal::ExecutionTrace<Point2> trace;
193 Point2 value = binary.traceExecution(values, trace, reinterpret_cast<char *>(traceStorage.get()));
199 expected25 << 0, 0, 0, 1, 0, 0, 0, 0, 0, 1;
201 expected22 << 1, 0, 0, 1;
204 std::optional<Binary::Record*> r = trace.record<Binary::Record>();
221 std::make_shared<Cal3_S2>());
222 double expected_error = old.
error(values);
242 typedef internal::UnaryExpression<Point2, Point3> Unary;
244 internal::ExecutionTrace<Point2> trace;
251 expected23 << 1, 0, 0, 0, 1, 0;
254 std::optional<Unary::Record*> r = trace.record<Unary::Record>();
262 std::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
278 double expected_error = old.
error(values);
295 std::shared_ptr<GaussianFactor> gf = f.
linearize(values);
303 std::shared_ptr<GaussianFactor> gf2 = f2.
linearize(values);
310 std::shared_ptr<GaussianFactor> gf3 = f3.
linearize(values);
330 std::vector<Matrix>
H(2);
337 std::shared_ptr<GaussianFactor> gf = f.
linearize(values);
338 std::shared_ptr<JacobianFactor> jf =
359 std::vector<Matrix>
H(1);
366 std::shared_ptr<GaussianFactor> gf = f.
linearize(values);
367 std::shared_ptr<JacobianFactor> jf =
388 std::vector<Matrix>
H(1);
395 std::shared_ptr<GaussianFactor> gf = f.
linearize(values);
396 std::shared_ptr<JacobianFactor> jf =
412 return R1 * (R2 *
R3);
431 std::vector<Matrix>
H(3);
440 std::shared_ptr<GaussianFactor> gf = f.
linearize(values);
441 std::shared_ptr<JacobianFactor> jf =
464 const double fd_step = 1
e-5;
465 const double tolerance = 1
e-5;
483 return a * x + b *
y;
488 const double tolerance = 1
e-5;
489 const double fd_step = 1
e-5;
530 static double combine3(
const double&
x,
const double&
y,
const double&
z,
533 if (H1) (*H1) << 1.0;
534 if (H2) (*H2) << 2.0;
535 if (H3) (*H3) << 3.0;
536 return x + 2.0 * y + 3.0 *
z;
540 const double tolerance = 1
e-5;
541 const double fd_step = 1
e-5;
557 EXPECT((sum2_.
keys() == std::set<Key>{1, 2, 3}))
561 EXPECT((sum3_.
keys() == std::set<Key>{1, 2, 3}))
565 EXPECT((sum4_.
keys() == std::set<Key>{1, 2, 3}))
572 auto model = noiseModel::Isotropic::Sigma(3, 1);
579 Matrix3
A =
Vector3(1, 2, 3).asDiagonal();
583 values.
insert<Matrix3>(0, A);
594 Matrix3
A =
Vector3(1, 2, 3).asDiagonal();
598 if (H1) *H1 << b.y(), b.z(), b.x(), 0, 0, 0;
605 auto model = noiseModel::Isotropic::Sigma(3, 1);
619 numericalDerivative11<Vector3, Point2>(
620 [&](
const Point2& a) {
return f(a, b, {}, {}); },
a),
635 gtsam::Rot3, gtsam::Point3,
636 gtsam::Rot3, gtsam::Point3> {
650 this->
initialize(expression({kR1, kV1, kR2, kV2}));
661 const std::array<gtsam::Key, NARY_EXPRESSION_SIZE> &
keys)
const override {
673 std::cout << s <<
"TestNaryFactor(" 674 << keyFormatter(Factor::keys_[0]) <<
"," 675 << keyFormatter(Factor::keys_[1]) <<
"," 676 << keyFormatter(Factor::keys_[2]) <<
"," 677 << keyFormatter(Factor::keys_[3]) <<
")\n";
679 this->noiseModel_->print(
" noise model: ");
684 double tol = 1
e-9)
const override {
686 return e !=
nullptr && Base::equals(*e,
tol) &&
691 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 693 friend class boost::serialization::access;
694 template <
class ARCHIVE>
695 void serialize(ARCHIVE &ar,
const unsigned int ) {
696 ar &boost::serialization::make_nvp(
698 boost::serialization::base_object<Base>(*
this));
699 ar &BOOST_SERIALIZATION_NVP(measured_);
713 values.
insert(
R(0), Rot3::Ypr(0.1, 0.2, 0.3));
715 values.
insert(
R(1), Rot3::Ypr(0.2, 0.5, 0.2));
719 std::vector<Matrix>
H(4);
728 auto model = noiseModel::Isotropic::Sigma(3, 1);
742 auto model = noiseModel::Isotropic::Sigma(3, 1);
758 auto model = noiseModel::Isotropic::Sigma(1, 1);
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Combine(double a, double b)
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
size_t dim() const override
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Vector9 id9(const Vector9 &v, OptionalJacobian< 9, 9 > H)
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
std::string serialize(const T &input)
serializes to a string
bool equals(const gtsam::NonlinearFactor &expected, double tol=1e-9) const override
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot2 R(Rot2::fromAngle(0.1))
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
noiseModel::Isotropic::shared_ptr Model
static double combine3(const double &x, const double &y, const double &z, OptionalJacobian< 1, 1 > H1, OptionalJacobian< 1, 1 > H2, OptionalJacobian< 1, 1 > H3)
double f2(const Vector2 &x)
void print(const std::string &s, const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
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
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
TEST(ExpressionFactor, Leaf)
KeysAndDims keysAndDims() const
std::unique_ptr< internal::ExecutionTraceStorage[]> allocAligned(size_t size)
Rot3 composeThree(const Rot3 &R1, const Rot3 &R2, const Rot3 &R3, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2, OptionalJacobian< 3, 3 > H3)
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
static void normalize(Signature::Row &row)
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
double operator()(const double &x, const double &y, OptionalJacobian< 1, 1 > H1, OptionalJacobian< 1, 1 > H2)
Point3 cross(const Point3 &p, const Point3 &q, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2)
cross product
void addExpressionFactor(const SharedNoiseModel &R, const T &z, const Expression< T > &h)
Test harness methods for expressions.
Eigen::Matrix< double, 9, 3 > Matrix93
gtsam::NonlinearFactor::shared_ptr clone() const override
#define EXPECT(condition)
Array< int, Dynamic, 1 > v
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
The most common 5DOF 3D->2D calibration.
Point3_ p_cam(x, &Pose3::transformTo, p)
Eigen::Matrix< double, 9, 9 > Matrix9
static sharedNode Leaf(Key key, const SymbolicFactorGraph &factors)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Reprojection of a LANDMARK to a 2D point.
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Expression< Point2 > uv_hat(uncalibrate< Cal3_S2 >, K, projection)
Matrix< Scalar, Dynamic, Dynamic > C
#define LONGS_EQUAL(expected, actual)
Vector9 wide(const Point3 &p, OptionalJacobian< 9, 3 > H)
noiseModel::Diagonal::shared_ptr SharedDiagonal
TestNaryFactor(gtsam::Key kR1, gtsam::Key kV1, gtsam::Key kR2, gtsam::Key kV2, const gtsam::SharedNoiseModel &model, const gtsam::Point3 &measured)
std::set< Key > keys() const
Return keys that play in this expression.
double error(const Values &c) const override
#define EXPECT_LONGS_EQUAL(expected, actual)
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
std::shared_ptr< This > shared_ptr
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
double f3(double x1, double x2)
void insert(Key j, const Value &val)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Jet< T, N > sqrt(const Jet< T, N > &f)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
static Point2 myUncal(const Cal3_S2 &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
a general SFM factor with an unknown calibration
gtsam::Expression< gtsam::Point3 > expression(const std::array< gtsam::Key, NARY_EXPRESSION_SIZE > &keys) const override
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
static Point2 project3(const Pose3 &pose, const Point3 &point, const Cal3_S2 &cal)
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
T traceExecution(const Values &values, internal::ExecutionTrace< T > &trace, char *traceStorage) const
trace execution, very unsafe
noiseModel::Base::shared_ptr SharedNoiseModel
Vector3 f(const Point2 &a, const Vector3 &b, OptionalJacobian< 3, 2 > H1, OptionalJacobian< 3, 3 > H2)
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)
size_t traceSize() const
Return size needed for memory buffer in traceExecution.
Expression< Vector3 > Vector3_
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 5 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const