23 using namespace gtsam;
28 values.
insert(key, org1_T_org2);
89 valA.
insert(keyA, orgA_T_1);
90 valB.
insert(keyB, orgB_T_2);
96 values.
insert(key, orgA_T_orgB);
123 valA.
insert(keyA, orgA_T_currA);
124 valB.
insert(keyB, orgB_T_currB);
130 values.
insert(key, orgA_T_orgB);
166 valA.
insert(keyA, orgA_T_currA);
167 valB.
insert(keyB, orgB_T_currB);
219 valA.
insert(keyA, orgA_T_1);
220 valB.
insert(keyB, orgB_T_2);
226 values.
insert(key, orgA_T_orgB);
228 std::vector<gtsam::Matrix> H_actual(1);
231 Matrix H1_actual = H_actual[0];
233 double stepsize = 1.0e-9;
234 Matrix H1_expected = gtsam::numericalDerivative11<Vector, Pose2>(std::bind(&
predictionError, std::placeholders::_1, key, g), orgA_T_orgB, stepsize);
const gtsam::Symbol key('X', 0)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
virtual const Values & optimize()
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Some functions to compute numerical derivatives.
NonlinearFactorGraph graph
void g(const string &key, int i)
static const SmartProjectionParams params
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Class compose(const Class &g) const
Class between(const Class &g) const
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
void insert(Key j, const Value &val)
Pose3 g2(g1.expmap(h *V1_g1))
Base class and parameters for nonlinear optimization algorithms.
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Gaussian::shared_ptr SharedGaussian