23 #include <boost/range/adaptor/reversed.hpp> 27 using namespace gtsam;
35 bool GaussianBayesNet::equals(
const This& bn,
double tol)
const 37 return Base::equals(bn, tol);
56 soln.
insert(cg->solve(soln));
64 gttic(GaussianBayesTree_optimizeGradientSearch);
90 result.
insert(cg->solveOtherRHS(result, rhs));
109 cg->solveTransposeInPlace(gy);
149 for (
Key key : cg->frontals()) {
150 ordering.push_back(
key);
163 return factorGraph.
jacobian(ordering);
169 const auto defaultOrdering = this->
ordering();
170 return matrix(defaultOrdering);
195 if (cg->get_model()) {
197 cg->get_model()->whitenInPlace(diag);
198 logDet += diag.unaryExpr([](
double x) {
return log(x); }).
sum();
201 cg->R().diagonal().unaryExpr([](
double x) {
return log(x); }).
sum();
208 void GaussianBayesNet::saveGraph(
const std::string&
s,
210 std::ofstream of(s.c_str());
211 of <<
"digraph G{\n";
215 Key me = frontals.front();
217 for (
Key p : parents)
218 of << keyFormatter(
p) <<
"->" << keyFormatter(me) << std::endl;
Matrix diag(const std::vector< Matrix > &Hs)
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
static enum @843 ordering
void determinant(const MatrixType &m)
double logDeterminant(const typename BAYESTREE::sharedClique &clique)
EIGEN_DEVICE_FUNC const LogReturnType log() const
VectorValues optimizeGradientSearch() const
double error(const VectorValues &x) const
VectorValues gradient(const VectorValues &x0) const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const mpreal sum(const mpreal tab[], const unsigned long int n, int &status, mp_rnd_t mode=mpreal::get_default_rnd())
Linear Factor Graph where all factors are Gaussians.
std::pair< Matrix, Vector > jacobian(const Ordering &ordering) const
void reverse(const MatrixType &m)
boost::shared_ptr< ConditionalType > sharedConditional
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Chordal Bayes Net, the result of eliminating a factor graph.
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
boost::iterator_range< typename JacobianFactor::const_iterator > Parents
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
iterator insert(const std::pair< Key, Vector > &key_value)
std::uint64_t Key
Integer nonlinear key type.
boost::iterator_range< typename JacobianFactor::const_iterator > Frontals
virtual VectorValues gradientAtZero() const