Go to the documentation of this file.
32 using namespace gtsam;
41 HybridNonlinearFactor::const_iterator const_it =
factor.
begin();
43 HybridNonlinearFactor::iterator it =
factor.
begin();
65 std::vector<NonlinearFactorValuePair> pairs{{
f0, 0.0}, {
f1, 0.0}};
84 0 Leaf Nonlinear factor on 2 keys
85 1 Leaf Nonlinear factor on 2 keys
98 auto model = noiseModel::Diagonal::Sigmas(
sigmas,
false);
113 continuousValues.
insert<
double>(
X(1), 0);
114 continuousValues.
insert<
double>(
X(2), 1);
117 hybridFactor.errorTree(continuousValues);
120 std::vector<DiscreteKey> discrete_keys = {
m1};
121 std::vector<double> errors = {0.5, 0};
static int runAllTests(TestResult &result)
#define EXPECT_LONGS_EQUAL(expected, actual)
#define EXPECT(condition)
Nonlinear hybrid factor graph that uses type erasure.
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
A Bayes net of Gaussian Conditionals indexed by discrete keys.
const_iterator begin() const
Provides additional testing facilities for common data structures.
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
Eigen::Matrix< double, 1, 1 > Vector1
const_iterator end() const
TEST(HybridNonlinearFactor, Constructor)
A set of nonlinear factors indexed by a set of discrete keys.
Linearized Hybrid factor graph that uses type erasure.
std::pair< Key, size_t > DiscreteKey
Implementation of a discrete-conditioned hybrid factor. Implements a joint discrete-continuous factor...
void insert(Key j, const Value &val)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
The matrix class, also used for vectors and row-vectors.
Implementation of a discrete-conditioned hybrid factor.
static HybridNonlinearFactor getHybridNonlinearFactor()
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:29