Fix call sites for HybridNonlinearFactor
parent
2c12e685ea
commit
bb4c3c95ab
|
@ -159,9 +159,8 @@ struct Switching {
|
||||||
|
|
||||||
// Add "motion models".
|
// Add "motion models".
|
||||||
for (size_t k = 0; k < K - 1; k++) {
|
for (size_t k = 0; k < K - 1; k++) {
|
||||||
KeyVector keys = {X(k), X(k + 1)};
|
|
||||||
auto motion_models = motionModels(k, between_sigma);
|
auto motion_models = motionModels(k, between_sigma);
|
||||||
nonlinearFactorGraph.emplace_shared<HybridNonlinearFactor>(keys, modes[k],
|
nonlinearFactorGraph.emplace_shared<HybridNonlinearFactor>(modes[k],
|
||||||
motion_models);
|
motion_models);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -388,7 +388,7 @@ TEST(HybridBayesNet, Sampling) {
|
||||||
auto one_motion =
|
auto one_motion =
|
||||||
std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
|
std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
|
||||||
nfg.emplace_shared<HybridNonlinearFactor>(
|
nfg.emplace_shared<HybridNonlinearFactor>(
|
||||||
KeyVector{X(0), X(1)}, DiscreteKey(M(0), 2),
|
DiscreteKey(M(0), 2),
|
||||||
std::vector<NonlinearFactor::shared_ptr>{zero_motion, one_motion});
|
std::vector<NonlinearFactor::shared_ptr>{zero_motion, one_motion});
|
||||||
|
|
||||||
DiscreteKey mode(M(0), 2);
|
DiscreteKey mode(M(0), 2);
|
||||||
|
|
|
@ -437,8 +437,7 @@ static HybridNonlinearFactorGraph createHybridNonlinearFactorGraph() {
|
||||||
std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
|
std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
|
||||||
std::vector<NonlinearFactor::shared_ptr> components = {zero_motion,
|
std::vector<NonlinearFactor::shared_ptr> components = {zero_motion,
|
||||||
one_motion};
|
one_motion};
|
||||||
nfg.emplace_shared<HybridNonlinearFactor>(KeyVector{X(0), X(1)}, m,
|
nfg.emplace_shared<HybridNonlinearFactor>(m, components);
|
||||||
components);
|
|
||||||
|
|
||||||
return nfg;
|
return nfg;
|
||||||
}
|
}
|
||||||
|
@ -591,9 +590,7 @@ TEST(HybridEstimation, ModeSelection) {
|
||||||
X(0), X(1), 0.0, noiseModel::Isotropic::Sigma(d, noise_tight));
|
X(0), X(1), 0.0, noiseModel::Isotropic::Sigma(d, noise_tight));
|
||||||
std::vector<NonlinearFactor::shared_ptr> components = {model0, model1};
|
std::vector<NonlinearFactor::shared_ptr> components = {model0, model1};
|
||||||
|
|
||||||
KeyVector keys = {X(0), X(1)};
|
HybridNonlinearFactor mf({M(0), 2}, components);
|
||||||
DiscreteKey modes(M(0), 2);
|
|
||||||
HybridNonlinearFactor mf(keys, modes, components);
|
|
||||||
|
|
||||||
initial.insert(X(0), 0.0);
|
initial.insert(X(0), 0.0);
|
||||||
initial.insert(X(1), 0.0);
|
initial.insert(X(1), 0.0);
|
||||||
|
@ -681,9 +678,7 @@ TEST(HybridEstimation, ModeSelection2) {
|
||||||
X(0), X(1), Z_3x1, noiseModel::Isotropic::Sigma(d, noise_tight));
|
X(0), X(1), Z_3x1, noiseModel::Isotropic::Sigma(d, noise_tight));
|
||||||
std::vector<NonlinearFactor::shared_ptr> components = {model0, model1};
|
std::vector<NonlinearFactor::shared_ptr> components = {model0, model1};
|
||||||
|
|
||||||
KeyVector keys = {X(0), X(1)};
|
HybridNonlinearFactor mf({M(0), 2}, components);
|
||||||
DiscreteKey modes(M(0), 2);
|
|
||||||
HybridNonlinearFactor mf(keys, modes, components);
|
|
||||||
|
|
||||||
initial.insert<Vector3>(X(0), Z_3x1);
|
initial.insert<Vector3>(X(0), Z_3x1);
|
||||||
initial.insert<Vector3>(X(1), Z_3x1);
|
initial.insert<Vector3>(X(1), Z_3x1);
|
||||||
|
|
|
@ -414,15 +414,13 @@ TEST(HybridGaussianISAM, NonTrivial) {
|
||||||
|
|
||||||
// Add odometry factor with discrete modes.
|
// Add odometry factor with discrete modes.
|
||||||
Pose2 odometry(1.0, 0.0, 0.0);
|
Pose2 odometry(1.0, 0.0, 0.0);
|
||||||
KeyVector contKeys = {W(0), W(1)};
|
|
||||||
auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
||||||
std::vector<NonlinearFactor::shared_ptr> components;
|
std::vector<NonlinearFactor::shared_ptr> components;
|
||||||
components.emplace_back(
|
components.emplace_back(
|
||||||
new PlanarMotionModel(W(0), W(1), odometry, noise_model)); // moving
|
new PlanarMotionModel(W(0), W(1), odometry, noise_model)); // moving
|
||||||
components.emplace_back(
|
components.emplace_back(
|
||||||
new PlanarMotionModel(W(0), W(1), Pose2(0, 0, 0), noise_model)); // still
|
new PlanarMotionModel(W(0), W(1), Pose2(0, 0, 0), noise_model)); // still
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey(M(1), 2), components);
|
||||||
contKeys, gtsam::DiscreteKey(M(1), 2), components);
|
|
||||||
|
|
||||||
// Add equivalent of ImuFactor
|
// Add equivalent of ImuFactor
|
||||||
fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
|
fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
|
||||||
|
@ -454,14 +452,12 @@ TEST(HybridGaussianISAM, NonTrivial) {
|
||||||
|
|
||||||
/*************** Run Round 3 ***************/
|
/*************** Run Round 3 ***************/
|
||||||
// Add odometry factor with discrete modes.
|
// Add odometry factor with discrete modes.
|
||||||
contKeys = {W(1), W(2)};
|
|
||||||
components.clear();
|
components.clear();
|
||||||
components.emplace_back(
|
components.emplace_back(
|
||||||
new PlanarMotionModel(W(1), W(2), odometry, noise_model)); // moving
|
new PlanarMotionModel(W(1), W(2), odometry, noise_model)); // moving
|
||||||
components.emplace_back(
|
components.emplace_back(
|
||||||
new PlanarMotionModel(W(1), W(2), Pose2(0, 0, 0), noise_model)); // still
|
new PlanarMotionModel(W(1), W(2), Pose2(0, 0, 0), noise_model)); // still
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey(M(2), 2), components);
|
||||||
contKeys, gtsam::DiscreteKey(M(2), 2), components);
|
|
||||||
|
|
||||||
// Add equivalent of ImuFactor
|
// Add equivalent of ImuFactor
|
||||||
fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
|
fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
|
||||||
|
@ -496,14 +492,12 @@ TEST(HybridGaussianISAM, NonTrivial) {
|
||||||
|
|
||||||
/*************** Run Round 4 ***************/
|
/*************** Run Round 4 ***************/
|
||||||
// Add odometry factor with discrete modes.
|
// Add odometry factor with discrete modes.
|
||||||
contKeys = {W(2), W(3)};
|
|
||||||
components.clear();
|
components.clear();
|
||||||
components.emplace_back(
|
components.emplace_back(
|
||||||
new PlanarMotionModel(W(2), W(3), odometry, noise_model)); // moving
|
new PlanarMotionModel(W(2), W(3), odometry, noise_model)); // moving
|
||||||
components.emplace_back(
|
components.emplace_back(
|
||||||
new PlanarMotionModel(W(2), W(3), Pose2(0, 0, 0), noise_model)); // still
|
new PlanarMotionModel(W(2), W(3), Pose2(0, 0, 0), noise_model)); // still
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey(M(3), 2), components);
|
||||||
contKeys, gtsam::DiscreteKey(M(3), 2), components);
|
|
||||||
|
|
||||||
// Add equivalent of ImuFactor
|
// Add equivalent of ImuFactor
|
||||||
fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
|
fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
|
||||||
|
|
|
@ -60,14 +60,14 @@ auto f1 = std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
|
||||||
// Test simple to complex constructors...
|
// Test simple to complex constructors...
|
||||||
TEST(HybridGaussianFactor, ConstructorVariants) {
|
TEST(HybridGaussianFactor, ConstructorVariants) {
|
||||||
using namespace test_constructor;
|
using namespace test_constructor;
|
||||||
HybridNonlinearFactor fromFactors({X(1), X(2)}, m1, {f0, f1});
|
HybridNonlinearFactor fromFactors(m1, {f0, f1});
|
||||||
|
|
||||||
std::vector<NonlinearFactorValuePair> pairs{{f0, 0.0}, {f1, 0.0}};
|
std::vector<NonlinearFactorValuePair> pairs{{f0, 0.0}, {f1, 0.0}};
|
||||||
HybridNonlinearFactor fromPairs({X(1), X(2)}, m1, pairs);
|
HybridNonlinearFactor fromPairs(m1, pairs);
|
||||||
assert_equal(fromFactors, fromPairs);
|
assert_equal(fromFactors, fromPairs);
|
||||||
|
|
||||||
HybridNonlinearFactor::FactorValuePairs decisionTree({m1}, pairs);
|
HybridNonlinearFactor::FactorValuePairs decisionTree({m1}, pairs);
|
||||||
HybridNonlinearFactor fromDecisionTree({X(1), X(2)}, {m1}, decisionTree);
|
HybridNonlinearFactor fromDecisionTree({m1}, decisionTree);
|
||||||
assert_equal(fromDecisionTree, fromPairs);
|
assert_equal(fromDecisionTree, fromPairs);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -75,7 +75,7 @@ TEST(HybridGaussianFactor, ConstructorVariants) {
|
||||||
// Test .print() output.
|
// Test .print() output.
|
||||||
TEST(HybridNonlinearFactor, Printing) {
|
TEST(HybridNonlinearFactor, Printing) {
|
||||||
using namespace test_constructor;
|
using namespace test_constructor;
|
||||||
HybridNonlinearFactor hybridFactor({X(1), X(2)}, {m1}, {f0, f1});
|
HybridNonlinearFactor hybridFactor({m1}, {f0, f1});
|
||||||
|
|
||||||
std::string expected =
|
std::string expected =
|
||||||
R"(Hybrid [x1 x2; 1]
|
R"(Hybrid [x1 x2; 1]
|
||||||
|
@ -101,7 +101,7 @@ static HybridNonlinearFactor getHybridNonlinearFactor() {
|
||||||
std::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
|
std::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
|
||||||
auto f1 =
|
auto f1 =
|
||||||
std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
|
std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
|
||||||
return HybridNonlinearFactor({X(1), X(2)}, m1, {f0, f1});
|
return HybridNonlinearFactor(m1, {f0, f1});
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -117,7 +117,6 @@ TEST(HybridNonlinearFactorGraph, Resize) {
|
||||||
|
|
||||||
/***************************************************************************/
|
/***************************************************************************/
|
||||||
namespace test_motion {
|
namespace test_motion {
|
||||||
KeyVector contKeys = {X(0), X(1)};
|
|
||||||
gtsam::DiscreteKey m1(M(1), 2);
|
gtsam::DiscreteKey m1(M(1), 2);
|
||||||
auto noise_model = noiseModel::Isotropic::Sigma(1, 1.0);
|
auto noise_model = noiseModel::Isotropic::Sigma(1, 1.0);
|
||||||
std::vector<NonlinearFactor::shared_ptr> components = {
|
std::vector<NonlinearFactor::shared_ptr> components = {
|
||||||
|
@ -139,8 +138,7 @@ TEST(HybridGaussianFactorGraph, Resize) {
|
||||||
auto discreteFactor = std::make_shared<DecisionTreeFactor>();
|
auto discreteFactor = std::make_shared<DecisionTreeFactor>();
|
||||||
hnfg.push_back(discreteFactor);
|
hnfg.push_back(discreteFactor);
|
||||||
|
|
||||||
auto dcFactor =
|
auto dcFactor = std::make_shared<HybridNonlinearFactor>(m1, components);
|
||||||
std::make_shared<HybridNonlinearFactor>(contKeys, m1, components);
|
|
||||||
hnfg.push_back(dcFactor);
|
hnfg.push_back(dcFactor);
|
||||||
|
|
||||||
Values linearizationPoint;
|
Values linearizationPoint;
|
||||||
|
@ -156,26 +154,6 @@ TEST(HybridGaussianFactorGraph, Resize) {
|
||||||
EXPECT_LONGS_EQUAL(gfg.size(), 0);
|
EXPECT_LONGS_EQUAL(gfg.size(), 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
/***************************************************************************
|
|
||||||
* Test that the HybridNonlinearFactor reports correctly if the number of
|
|
||||||
* continuous keys provided do not match the keys in the factors.
|
|
||||||
*/
|
|
||||||
TEST(HybridGaussianFactorGraph, HybridNonlinearFactor) {
|
|
||||||
using namespace test_motion;
|
|
||||||
|
|
||||||
auto nonlinearFactor = std::make_shared<BetweenFactor<double>>(
|
|
||||||
X(0), X(1), 0.0, Isotropic::Sigma(1, 0.1));
|
|
||||||
auto discreteFactor = std::make_shared<DecisionTreeFactor>();
|
|
||||||
|
|
||||||
// Check for exception when number of continuous keys are under-specified.
|
|
||||||
THROWS_EXCEPTION(
|
|
||||||
std::make_shared<HybridNonlinearFactor>(KeyVector{X(0)}, m1, components));
|
|
||||||
|
|
||||||
// Check for exception when number of continuous keys are too many.
|
|
||||||
THROWS_EXCEPTION(std::make_shared<HybridNonlinearFactor>(
|
|
||||||
KeyVector{X(0), X(1), X(2)}, m1, components));
|
|
||||||
}
|
|
||||||
|
|
||||||
/*****************************************************************************
|
/*****************************************************************************
|
||||||
* Test push_back on HFG makes the correct distinction.
|
* Test push_back on HFG makes the correct distinction.
|
||||||
*/
|
*/
|
||||||
|
@ -828,14 +806,12 @@ TEST(HybridNonlinearFactorGraph, DefaultDecisionTree) {
|
||||||
|
|
||||||
// Add odometry factor
|
// Add odometry factor
|
||||||
Pose2 odometry(2.0, 0.0, 0.0);
|
Pose2 odometry(2.0, 0.0, 0.0);
|
||||||
KeyVector contKeys = {X(0), X(1)};
|
|
||||||
auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
||||||
std::vector<NonlinearFactor::shared_ptr> motion_models = {
|
std::vector<NonlinearFactor::shared_ptr> motion_models = {
|
||||||
std::make_shared<PlanarMotionModel>(X(0), X(1), Pose2(0, 0, 0),
|
std::make_shared<PlanarMotionModel>(X(0), X(1), Pose2(0, 0, 0),
|
||||||
noise_model),
|
noise_model),
|
||||||
std::make_shared<PlanarMotionModel>(X(0), X(1), odometry, noise_model)};
|
std::make_shared<PlanarMotionModel>(X(0), X(1), odometry, noise_model)};
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey{M(1), 2}, motion_models);
|
||||||
contKeys, gtsam::DiscreteKey(M(1), 2), motion_models);
|
|
||||||
|
|
||||||
// Add Range-Bearing measurements to from X0 to L0 and X1 to L1.
|
// Add Range-Bearing measurements to from X0 to L0 and X1 to L1.
|
||||||
// create a noise model for the landmark measurements
|
// create a noise model for the landmark measurements
|
||||||
|
@ -901,7 +877,7 @@ static HybridNonlinearFactorGraph CreateFactorGraph(
|
||||||
std::vector<NonlinearFactorValuePair> factors{{f0, model0->negLogConstant()},
|
std::vector<NonlinearFactorValuePair> factors{{f0, model0->negLogConstant()},
|
||||||
{f1, model1->negLogConstant()}};
|
{f1, model1->negLogConstant()}};
|
||||||
|
|
||||||
HybridNonlinearFactor mixtureFactor({X(0), X(1)}, m1, factors);
|
HybridNonlinearFactor mixtureFactor(m1, factors);
|
||||||
|
|
||||||
HybridNonlinearFactorGraph hfg;
|
HybridNonlinearFactorGraph hfg;
|
||||||
hfg.push_back(mixtureFactor);
|
hfg.push_back(mixtureFactor);
|
||||||
|
|
|
@ -433,15 +433,13 @@ TEST(HybridNonlinearISAM, NonTrivial) {
|
||||||
/*************** Run Round 2 ***************/
|
/*************** Run Round 2 ***************/
|
||||||
// Add odometry factor with discrete modes.
|
// Add odometry factor with discrete modes.
|
||||||
Pose2 odometry(1.0, 0.0, 0.0);
|
Pose2 odometry(1.0, 0.0, 0.0);
|
||||||
KeyVector contKeys = {W(0), W(1)};
|
|
||||||
auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
||||||
auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
|
auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
|
||||||
noise_model),
|
noise_model),
|
||||||
moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
|
moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
|
||||||
noise_model);
|
noise_model);
|
||||||
std::vector<NonlinearFactor::shared_ptr> components{moving, still};
|
std::vector<NonlinearFactor::shared_ptr> components{moving, still};
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey(M(1), 2), components);
|
||||||
contKeys, gtsam::DiscreteKey(M(1), 2), components);
|
|
||||||
|
|
||||||
// Add equivalent of ImuFactor
|
// Add equivalent of ImuFactor
|
||||||
fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
|
fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
|
||||||
|
@ -473,14 +471,12 @@ TEST(HybridNonlinearISAM, NonTrivial) {
|
||||||
|
|
||||||
/*************** Run Round 3 ***************/
|
/*************** Run Round 3 ***************/
|
||||||
// Add odometry factor with discrete modes.
|
// Add odometry factor with discrete modes.
|
||||||
contKeys = {W(1), W(2)};
|
|
||||||
still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
|
still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
|
||||||
noise_model);
|
noise_model);
|
||||||
moving =
|
moving =
|
||||||
std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
|
std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
|
||||||
components = {moving, still};
|
components = {moving, still};
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey(M(2), 2), components);
|
||||||
contKeys, gtsam::DiscreteKey(M(2), 2), components);
|
|
||||||
|
|
||||||
// Add equivalent of ImuFactor
|
// Add equivalent of ImuFactor
|
||||||
fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
|
fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
|
||||||
|
@ -515,14 +511,12 @@ TEST(HybridNonlinearISAM, NonTrivial) {
|
||||||
|
|
||||||
/*************** Run Round 4 ***************/
|
/*************** Run Round 4 ***************/
|
||||||
// Add odometry factor with discrete modes.
|
// Add odometry factor with discrete modes.
|
||||||
contKeys = {W(2), W(3)};
|
|
||||||
still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
|
still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
|
||||||
noise_model);
|
noise_model);
|
||||||
moving =
|
moving =
|
||||||
std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
|
std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
|
||||||
components = {moving, still};
|
components = {moving, still};
|
||||||
fg.emplace_shared<HybridNonlinearFactor>(
|
fg.emplace_shared<HybridNonlinearFactor>(DiscreteKey(M(3), 2), components);
|
||||||
contKeys, gtsam::DiscreteKey(M(3), 2), components);
|
|
||||||
|
|
||||||
// Add equivalent of ImuFactor
|
// Add equivalent of ImuFactor
|
||||||
fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
|
fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
|
||||||
|
|
Loading…
Reference in New Issue