16 #include <boost/assign/std/vector.hpp> 20 using namespace gtsam;
31 TEST( testLinearContainerFactor, generic_jacobian_factor ) {
35 0.0, 2.63624).finished();
37 -0.0455167, -0.0443573,
38 -0.0222154, -0.102489).finished();
64 TEST( testLinearContainerFactor, jacobian_factor_withlinpoints ) {
68 0.0, 2.63624).finished();
70 -0.0455167, -0.0443573,
71 -0.0222154, -0.102489).finished();
103 delta.
at(l1) = delta_l1;
104 delta.
at(
l2) = delta_l2;
106 double expError = expLinFactor.
error(delta);
112 Vector bprime = b - A1 * delta_l1 - A2 * delta_l2;
118 TEST( testLinearContainerFactor, generic_hessian_factor ) {
121 Matrix G13 = (
Matrix(1, 3) << 3.0, 6.0, 9.0).finished();
124 0.0, 6.0).finished();
126 1.0, 2.0, 4.0).finished();
130 0.0, 0.0, 9.0).finished();
139 G11, G12, G13, g1, G22, G23, g2, G33, g3, f);
156 TEST( testLinearContainerFactor, hessian_factor_withlinpoints ) {
163 0.0, 0.0, 9.0).finished();
167 4.0, 6.0).finished();
172 0.0, 0.6).finished();
180 G << G11, G12, Matrix::Zero(2,3), G22;
184 Values linearizationPoint, expLinPoints;
187 expLinPoints = linearizationPoint;
205 delta.
at(l1) = delta_l1;
206 delta.
at(
x1) = delta_x1;
207 delta.
at(
x2) = delta_x2;
211 double expError = initFactor.
error(delta);
216 Vector dv = (
Vector(5) << 3.0, 4.0, 0.5, 1.0, 2.0).finished();
221 Vector g1_prime = g_prime.head(3);
222 Vector g2_prime = g_prime.tail(2);
223 double f_prime = f + dv.transpose() * G.selfadjointView<
Eigen::Upper>() * dv - 2.0 * dv.transpose() *
g;
224 HessianFactor expNewFactor(
x1, l1, G11, G12, g1_prime, G22, g2_prime, f_prime);
229 TEST( testLinearContainerFactor, creation ) {
231 Key l1 = 11,
l3 = 13, l5 = 15;
236 l3, I_2x2, l5, 2.0 * I_2x2,
Z_2x1, model));
242 exp_values = full_values;
255 TEST( testLinearContainerFactor, jacobian_relinearize )
278 double expected_error = betweenFactor.
error(linpoint2);
279 double actual_error = jacobianContainer.
error(linpoint2);
289 TEST( testLinearContainerFactor, hessian_relinearize )
312 double expected_error = betweenFactor.
error(linpoint2);
313 double actual_error = hessianContainer.
error(linpoint2);
Provides additional testing facilities for common data structures.
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
double error(const Values &c) const override
const gtsam::noiseModel::Diagonal::shared_ptr diag_model2
Pose2 poseA2(2.0, 0.0, 0.0)
static int runAllTests(TestResult &result)
Pose2 poseA1(0.0, 0.0, 0.0)
VectorValues zeroVectors() const
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
JacobiRotation< float > G
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
GaussianFactor::shared_ptr clone() const override
Values retract(const VectorValues &delta) const
Point2 landmark1(5.0, 1.5)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
void g(const string &key, int i)
bool assert_container_equality(const std::map< size_t, V2 > &expected, const std::map< size_t, V2 > &actual)
double error(const VectorValues &c) const override
const Symbol key1('v', 1)
Point2 landmark2(7.0, 1.5)
GaussianFactor::shared_ptr clone() const override
GTSAM_EXPORT bool isHessian() const
#define EXPECT(condition)
const boost::optional< Values > & linearizationPoint() const
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static const Symbol l3('l', 3)
Contains the HessianFactor class, a general quadratic factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(testLinearContainerFactor, generic_jacobian_factor)
boost::shared_ptr< Diagonal > shared_ptr
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define EXPECT_LONGS_EQUAL(expected, actual)
const KeyVector & keys() const
Access the factor's involved variable keys.
GTSAM_EXPORT bool isJacobian() const
const Symbol key2('v', 2)
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
double error(const VectorValues &c) const override
A Gaussian factor using the canonical parameters (information form)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Pose3 g2(g1.expmap(h *V1_g1))
GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values &c) const override
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
GTSAM_EXPORT double error(const Values &c) const override
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
std::uint64_t Key
Integer nonlinear key type.
bool hasLinearizationPoint() const
noiseModel::Base::shared_ptr SharedNoiseModel
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)