26 #include <boost/assign/std/map.hpp> 30 using namespace gtsam;
37 graph.
add(AI,
"1 0 0 1");
38 graph.
add(AI,
"1 1 1 0");
39 graph.
add(A & AI,
"1 1 1 0 1 1 1 1 0 1 1 1");
40 graph.
add(ME,
"0 1 0 0");
41 graph.
add(ME,
"1 1 1 0");
42 graph.
add(A & ME,
"1 1 1 0 1 1 1 1 0 1 1 1");
43 graph.
add(PC,
"1 0 1 0");
44 graph.
add(PC,
"1 1 1 0");
45 graph.
add(A & PC,
"1 1 1 0 1 1 1 1 0 1 1 1");
46 graph.
add(ME & AI,
"0 1 1 1 1 0 1 1 1 1 0 1 1 1 1 0");
47 graph.
add(PC & ME,
"0 1 1 1 1 0 1 1 1 1 0 1 1 1 1 0");
48 graph.
add(PC & AI,
"0 1 1 1 1 0 1 1 1 1 0 1 1 1 1 0");
80 graph.
add(P1,
"0.9 0.3");
81 graph.
add(
P2,
"0.9 0.6");
82 graph.
add(P1 &
P2,
"4 1 10 4");
93 graph.
add(P3,
"0.9 0.2 0.5");
94 graph.
add(P1 & P2 & P3,
"1 2 3 4 5 6 7 8 9 10 11 12");
126 graph.
add(A &
C,
"3 1 1 3");
127 graph.
add(C &
B,
"3 1 1 3");
132 frontalKeys +=
Key(0);
140 Signature signature((C | B, A) =
"9/1 1/1 1/1 1/9");
144 expected.
add(signature);
152 expected.
add(B | A =
"5/3 3/5");
153 expected.
add(A %
"1/1");
171 insert(expectedValues)(0, 0)(1, 0)(2, 0);
184 graph.
add(
C &
A,
"0.2 0.8 0.3 0.7");
185 graph.
add(
C & B,
"0.1 0.9 0.4 0.6");
192 insert(expectedMPE)(0, 0)(1, 1)(2, 1);
204 graph.
add(
S,
"0.55 0.45");
205 graph.
add(
S &
C,
"0.05 0.95 0.01 0.99");
206 graph.
add(C &
T1,
"0.80 0.20 0.20 0.80");
207 graph.
add(
S & C & T2,
"0.80 0.20 0.20 0.80 0.95 0.05 0.05 0.95");
208 graph.
add(T1 & T2 &
A,
"1 0 0 1 0 1 1 0");
215 insert(expectedMPE)(4, 0)(2, 0)(3, 1)(0, 1)(1, 1);
239 VariableIndexOrdered structure(graph);
240 typedef EliminationTreeOrdered<DiscreteFactor> ETree;
241 ETree::shared_ptr eTree = ETree::Create(graph, structure);
269 Key2(
const std::string&
name,
size_t cardinality = 2) :
270 wff_(name), cardinality_(cardinality) {
272 const std::string&
name()
const {
285 Factor2(
const std::string&
s) :
288 Factor2(
const Key2&
key) :
292 friend std::ostream&
operator <<(std::ostream &
os,
const Factor2 &
f);
303 return Factor2(
"-" + key.name());
308 return Factor2(std::string(
"(") + factor1.wff_ +
" || " + factor2.wff_ +
")");
312 Factor2
operator &&(
const Factor2 &factor1,
const Factor2 &factor2) {
313 return Factor2(std::string(
"(") + factor1.wff_ +
" && " + factor2.wff_ +
")");
317 Factor2
operator >>(
const Factor2 &factor1,
const Factor2 &factor2) {
318 return Factor2(std::string(
"(") + factor1.wff_ +
" >> " + factor2.wff_ +
")");
321 struct Graph2:
public std::list<Factor2> {
338 for(
const Factor2& f: graph)
346 Key2
M(
"Mythical"),
I(
"Immortal"),
A(
"Mammal"),
H(
"Horned"),
G(
"Magical");
351 unicorns += (-
M) >> (-
I && A);
352 unicorns += (
I || A) >>
H;
Matrix< RealScalar, Dynamic, Dynamic > M
void add(const DiscreteKey &j, SOURCE table)
static int runAllTests(TestResult &result)
JacobiRotation< float > G
static enum @843 ordering
boost::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
const mpreal operator>>(const mpreal &v, const unsigned long int k)
DiscreteFactor::sharedValues optimize() const
void add(const Signature &s)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
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
Matrix< SCALARB, Dynamic, Dynamic > B
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
EIGEN_DEVICE_FUNC const CwiseBinaryOp< internal::scalar_boolean_and_op, const Derived, const OtherDerived > operator&&(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
EIGEN_DEVICE_FUNC const CwiseBinaryOp< internal::scalar_boolean_or_op, const Derived, const OtherDerived > operator||(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
std::ostream & operator<<(std::ostream &s, const Jet< T, N > &z)
std::pair< Key, size_t > DiscreteKey
#define EXPECT(condition)
TEST(DiscreteFactorGraph, test)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > eliminate(Eliminate function) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const mpreal sum(const mpreal tab[], const unsigned long int n, int &status, mp_rnd_t mode=mpreal::get_default_rnd())
Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree.
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Matrix< Scalar, Dynamic, Dynamic > C
static const Point3 P2(3.5,-8.2, 4.2)
boost::shared_ptr< This > shared_ptr
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define EXPECT_LONGS_EQUAL(expected, actual)
ofstream os("timeSchurFactors.csv")
TEST_UNSAFE(DiscreteFactorGraph, debugScheduler)
boost::shared_ptr< Values > sharedValues
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
boost::shared_ptr< DecisionTreeFactor > shared_ptr
boost::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
boost::shared_ptr< This > shared_ptr
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
Jet< T, N > operator-(const Jet< T, N > &f)
Annotation for function names.
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
std::uint64_t Key
Integer nonlinear key type.
DecisionTreeFactor product() const
void product(const MatrixType &m)
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))