27 using namespace gtsam;
38 bool GaussianBayesNet::equals(
const This& bn,
double tol)
const 40 return Base::equals(bn, tol);
57 solution.
insert((*it)->solve(solution));
65 return sample(result, rng);
69 std::mt19937_64*
rng)
const {
91 gttic(GaussianBayesTree_optimizeGradientSearch);
108 for (
const auto& gc : *
this) {
109 if (gc) sum += gc->error(x);
117 for (
const auto& gc : *
this) {
118 if (gc) sum += gc->logProbability(x);
125 return exp(logProbability(x));
135 result.
insert((*it)->solveOtherRHS(result, rhs));
154 cg->solveTransposeInPlace(gy);
194 for (
Key key : cg->frontals()) {
195 ordering.push_back(
key);
208 return factorGraph.
jacobian(ordering);
214 const auto defaultOrdering = this->
ordering();
215 return matrix(defaultOrdering);
240 logDet += cg->logDeterminant();
const gtsam::Symbol key('X', 0)
VectorValues optimizeGradientSearch() const
void determinant(const MatrixType &m)
double logDeterminant(const typename BAYESTREE::sharedClique &clique)
iterator insert(const std::pair< Key, Vector > &key_value)
static enum @1107 ordering
std::reverse_iterator< Iterator > make_reverse_iterator(Iterator i)
std::shared_ptr< ConditionalType > sharedConditional
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
Linear Factor Graph where all factors are Gaussians.
std::pair< Matrix, Vector > jacobian(const Ordering &ordering) const
static EIGEN_DEPRECATED const end_t end
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Chordal Bayes Net, the result of eliminating a factor graph.
static std::mt19937_64 kRandomNumberGenerator(42)
VectorValues gradient(const VectorValues &x0) const
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
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 x
virtual VectorValues gradientAtZero() const
std::uint64_t Key
Integer nonlinear key type.