29 using namespace gtsam;
36 static SymbolicConditional::shared_ptr
56 SymbolicConditional::shared_ptr
92 writer.positionHints.emplace(
'x', 1);
93 writer.boxes.emplace(
A(1));
94 writer.boxes.emplace(
A(2));
106 " var6989586621679009793[label=\"a1\", pos=\"1,2!\", shape=box];\n" 107 " var6989586621679009794[label=\"a2\", pos=\"2,2!\", shape=box];\n" 108 " var8646911284551352321[label=\"x1\", pos=\"1,1!\"];\n" 109 " var8646911284551352322[label=\"x2\", pos=\"2,1!\"];\n" 110 " var8646911284551352323[label=\"x3\", pos=\"3,1!\"];\n" 112 " var8646911284551352321->var8646911284551352322\n" 113 " var6989586621679009793->var8646911284551352322\n" 114 " var8646911284551352322->var8646911284551352323\n" 115 " var6989586621679009794->var8646911284551352323\n" Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
GTSAM_EXPORT bool equals(const This &bn, double tol=1e-9) const
Concept check for values that can be used in unit tests.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
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)
void dot(std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
Output to graphviz format, stream version.
double f2(const Vector2 &x)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
static const KeyFormatter DefaultKeyFormatter
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(SymbolicBayesNet, equals)
Matrix< Scalar, Dynamic, Dynamic > C
DotWriter is a helper class for writing graphviz .dot files.
typedef and functions to augment Eigen's VectorXd
void saveGraph(const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
output to file with graphviz format.
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
static SymbolicConditional::shared_ptr L(new SymbolicConditional(_L_, _B_))
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
std::uint64_t Key
Integer nonlinear key type.
std::map< char, double > positionHints