`optional<Ordering>` and `auto` modernization
parent
e20494324f
commit
bc511a26ec
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization,
|
||||
EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering)
|
||||
boost::optional<const Ordering &> ordering)
|
||||
: values_(solution), factorization_(factorization) {
|
||||
gttic(MarginalsConstructor);
|
||||
graph_ = *graph.linearize(solution);
|
||||
|
|
@ -36,12 +36,12 @@ Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution,
|
|||
|
||||
/* ************************************************************************* */
|
||||
Marginals::Marginals(const GaussianFactorGraph& graph, const VectorValues& solution, Factorization factorization,
|
||||
EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering)
|
||||
boost::optional<const Ordering &> ordering)
|
||||
: graph_(graph), factorization_(factorization) {
|
||||
gttic(MarginalsConstructor);
|
||||
Values vals;
|
||||
for (const VectorValues::KeyValuePair& v: solution) {
|
||||
vals.insert(v.first, v.second);
|
||||
for (const auto& keyValue: solution) {
|
||||
vals.insert(keyValue.first, keyValue.second);
|
||||
}
|
||||
values_ = vals;
|
||||
computeBayesTree(ordering);
|
||||
|
|
@ -49,16 +49,15 @@ Marginals::Marginals(const GaussianFactorGraph& graph, const VectorValues& solut
|
|||
|
||||
/* ************************************************************************* */
|
||||
Marginals::Marginals(const GaussianFactorGraph& graph, const Values& solution, Factorization factorization,
|
||||
EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering)
|
||||
boost::optional<const Ordering &> ordering)
|
||||
: graph_(graph), values_(solution), factorization_(factorization) {
|
||||
gttic(MarginalsConstructor);
|
||||
computeBayesTree(ordering);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Marginals::computeBayesTree(EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering) {
|
||||
void Marginals::computeBayesTree(boost::optional<const Ordering &> ordering) {
|
||||
// Compute BayesTree
|
||||
factorization_ = factorization;
|
||||
if(factorization_ == CHOLESKY)
|
||||
bayesTree_ = *graph_.eliminateMultifrontal(ordering, EliminatePreferCholesky);
|
||||
else if(factorization_ == QR)
|
||||
|
|
@ -145,7 +144,7 @@ JointMarginal Marginals::jointMarginalInformation(const KeyVector& variables) co
|
|||
// Get dimensions from factor graph
|
||||
std::vector<size_t> dims;
|
||||
dims.reserve(variablesSorted.size());
|
||||
for(Key key: variablesSorted) {
|
||||
for(const auto& key: variablesSorted) {
|
||||
dims.push_back(values_.at(key).dim());
|
||||
}
|
||||
|
||||
|
|
@ -162,7 +161,7 @@ VectorValues Marginals::optimize() const {
|
|||
void JointMarginal::print(const std::string& s, const KeyFormatter& formatter) const {
|
||||
cout << s << "Joint marginal on keys ";
|
||||
bool first = true;
|
||||
for(Key key: keys_) {
|
||||
for(const auto& key: keys_) {
|
||||
if(!first)
|
||||
cout << ", ";
|
||||
else
|
||||
|
|
|
|||
|
|
@ -58,7 +58,7 @@ public:
|
|||
* @param ordering An optional variable ordering for elimination.
|
||||
*/
|
||||
Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization = CHOLESKY,
|
||||
EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering = boost::none);
|
||||
boost::optional<const Ordering &> ordering = boost::none);
|
||||
|
||||
/** Construct a marginals class from a linear factor graph.
|
||||
* @param graph The factor graph defining the full joint density on all variables.
|
||||
|
|
@ -67,7 +67,7 @@ public:
|
|||
* @param ordering An optional variable ordering for elimination.
|
||||
*/
|
||||
Marginals(const GaussianFactorGraph& graph, const Values& solution, Factorization factorization = CHOLESKY,
|
||||
EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering = boost::none);
|
||||
boost::optional<const Ordering &> ordering = boost::none);
|
||||
|
||||
/** Construct a marginals class from a linear factor graph.
|
||||
* @param graph The factor graph defining the full joint density on all variables.
|
||||
|
|
@ -76,7 +76,7 @@ public:
|
|||
* @param ordering An optional variable ordering for elimination.
|
||||
*/
|
||||
Marginals(const GaussianFactorGraph& graph, const VectorValues& solution, Factorization factorization = CHOLESKY,
|
||||
EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering = boost::none);
|
||||
boost::optional<const Ordering &> ordering = boost::none);
|
||||
|
||||
/** print */
|
||||
void print(const std::string& str = "Marginals: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
||||
|
|
@ -103,7 +103,7 @@ public:
|
|||
protected:
|
||||
|
||||
/** Compute the Bayes Tree as a helper function to the constructor */
|
||||
void computeBayesTree(EliminateableFactorGraph<GaussianFactorGraph>::OptionalOrdering ordering);
|
||||
void computeBayesTree(boost::optional<const Ordering &> ordering);
|
||||
|
||||
};
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue