Removed print and cout statements.
parent
056aed4419
commit
ca792cf041
|
@ -129,10 +129,7 @@ namespace gtsam {
|
||||||
Vector soln = get_R().triangularView<Eigen::Upper>().solve(xS);
|
Vector soln = get_R().triangularView<Eigen::Upper>().solve(xS);
|
||||||
|
|
||||||
// Check for indeterminant solution
|
// Check for indeterminant solution
|
||||||
if(soln.hasNaN()) {
|
if(soln.hasNaN()) throw IndeterminantLinearSystemException(keys().front());
|
||||||
std::cout << "GaussianConditional::solve failed: solution has NaN!!" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(keys().front());
|
|
||||||
}
|
|
||||||
|
|
||||||
// TODO, do we not have to scale by sigmas here? Copy/paste bug
|
// TODO, do we not have to scale by sigmas here? Copy/paste bug
|
||||||
|
|
||||||
|
@ -183,10 +180,7 @@ namespace gtsam {
|
||||||
frontalVec = gtsam::backSubstituteUpper(frontalVec, Matrix(get_R()));
|
frontalVec = gtsam::backSubstituteUpper(frontalVec, Matrix(get_R()));
|
||||||
|
|
||||||
// Check for indeterminant solution
|
// Check for indeterminant solution
|
||||||
if (frontalVec.hasNaN()) {
|
if (frontalVec.hasNaN()) throw IndeterminantLinearSystemException(this->keys().front());
|
||||||
std::cout << "GaussianConditional::solveTransposeInPlace failed: frontalVec has NaN!!" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(this->keys().front());
|
|
||||||
}
|
|
||||||
|
|
||||||
for (const_iterator it = beginParents(); it!= endParents(); it++)
|
for (const_iterator it = beginParents(); it!= endParents(); it++)
|
||||||
gtsam::transposeMultiplyAdd(-1.0, Matrix(getA(it)), frontalVec, gy[*it]);
|
gtsam::transposeMultiplyAdd(-1.0, Matrix(getA(it)), frontalVec, gy[*it]);
|
||||||
|
@ -214,4 +208,3 @@ namespace gtsam {
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -641,7 +641,6 @@ EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys)
|
||||||
// Erase the eliminated keys in the remaining factor
|
// Erase the eliminated keys in the remaining factor
|
||||||
jointFactor->keys_.erase(jointFactor->begin(), jointFactor->begin() + numberOfKeysToEliminate);
|
jointFactor->keys_.erase(jointFactor->begin(), jointFactor->begin() + numberOfKeysToEliminate);
|
||||||
} catch(CholeskyFailed&) {
|
} catch(CholeskyFailed&) {
|
||||||
std::cout << "EliminateCholesky failed!" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(keys.front());
|
throw IndeterminantLinearSystemException(keys.front());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -116,10 +116,8 @@ JacobianFactor::JacobianFactor(const HessianFactor& factor) :
|
||||||
boost::tie(maxrank, success) = choleskyCareful(Ab_.matrix());
|
boost::tie(maxrank, success) = choleskyCareful(Ab_.matrix());
|
||||||
|
|
||||||
// Check for indefinite system
|
// Check for indefinite system
|
||||||
if (!success) {
|
if (!success)
|
||||||
std::cout << "JacobianFactor constructor from HessianFactor failed!" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(factor.keys().front());
|
throw IndeterminantLinearSystemException(factor.keys().front());
|
||||||
}
|
|
||||||
|
|
||||||
// Zero out lower triangle
|
// Zero out lower triangle
|
||||||
Ab_.matrix().topRows(maxrank).triangularView<Eigen::StrictlyLower>() =
|
Ab_.matrix().topRows(maxrank).triangularView<Eigen::StrictlyLower>() =
|
||||||
|
@ -693,10 +691,8 @@ GaussianConditional::shared_ptr JacobianFactor::splitConditional(
|
||||||
Ab_.rowEnd() = Ab_.rowStart() + frontalDim;
|
Ab_.rowEnd() = Ab_.rowStart() + frontalDim;
|
||||||
SharedDiagonal conditionalNoiseModel;
|
SharedDiagonal conditionalNoiseModel;
|
||||||
if (model_) {
|
if (model_) {
|
||||||
if ((DenseIndex) model_->dim() < frontalDim) {
|
if ((DenseIndex) model_->dim() < frontalDim)
|
||||||
std::cout << "Jacobian::splitConditional failed" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(this->keys().front());
|
throw IndeterminantLinearSystemException(this->keys().front());
|
||||||
}
|
|
||||||
conditionalNoiseModel = noiseModel::Diagonal::Sigmas(
|
conditionalNoiseModel = noiseModel::Diagonal::Sigmas(
|
||||||
model_->sigmas().segment(Ab_.rowStart(), Ab_.rows()));
|
model_->sigmas().segment(Ab_.rowStart(), Ab_.rows()));
|
||||||
}
|
}
|
||||||
|
|
|
@ -86,10 +86,7 @@ namespace gtsam
|
||||||
Vector soln = c.get_R().triangularView<Eigen::Upper>().solve(xS);
|
Vector soln = c.get_R().triangularView<Eigen::Upper>().solve(xS);
|
||||||
|
|
||||||
// Check for indeterminant solution
|
// Check for indeterminant solution
|
||||||
if(soln.hasNaN()) {
|
if(soln.hasNaN()) throw IndeterminantLinearSystemException(c.keys().front());
|
||||||
std::cout << "linearAlgorithms::OptimizeClique failed: solution has NaN!" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(c.keys().front());
|
|
||||||
}
|
|
||||||
|
|
||||||
// Insert solution into a VectorValues
|
// Insert solution into a VectorValues
|
||||||
DenseIndex vectorPosition = 0;
|
DenseIndex vectorPosition = 0;
|
||||||
|
|
|
@ -115,7 +115,6 @@ template<class CLIQUE>
|
||||||
bool optimizeWildfireNode(const boost::shared_ptr<CLIQUE>& clique, double threshold,
|
bool optimizeWildfireNode(const boost::shared_ptr<CLIQUE>& clique, double threshold,
|
||||||
FastSet<Key>& changed, const FastSet<Key>& replaced, VectorValues& delta, size_t& count)
|
FastSet<Key>& changed, const FastSet<Key>& replaced, VectorValues& delta, size_t& count)
|
||||||
{
|
{
|
||||||
//clique->print("Input clique: ");
|
|
||||||
// if none of the variables in this clique (frontal and separator!) changed
|
// if none of the variables in this clique (frontal and separator!) changed
|
||||||
// significantly, then by the running intersection property, none of the
|
// significantly, then by the running intersection property, none of the
|
||||||
// cliques in the children need to be processed
|
// cliques in the children need to be processed
|
||||||
|
@ -193,10 +192,7 @@ bool optimizeWildfireNode(const boost::shared_ptr<CLIQUE>& clique, double thresh
|
||||||
Vector soln = c.get_R().triangularView<Eigen::Upper>().solve(xS);
|
Vector soln = c.get_R().triangularView<Eigen::Upper>().solve(xS);
|
||||||
|
|
||||||
// Check for indeterminant solution
|
// Check for indeterminant solution
|
||||||
if(soln.hasNaN()) {
|
if(soln.hasNaN()) throw IndeterminantLinearSystemException(c.keys().front());
|
||||||
std::cout << "iSAM2 failed: solution has NaN!!" << std::endl;
|
|
||||||
throw IndeterminantLinearSystemException(c.keys().front());
|
|
||||||
}
|
|
||||||
|
|
||||||
// Insert solution into a VectorValues
|
// Insert solution into a VectorValues
|
||||||
DenseIndex vectorPosition = 0;
|
DenseIndex vectorPosition = 0;
|
||||||
|
@ -307,4 +303,3 @@ int calculate_nnz(const boost::shared_ptr<CLIQUE>& clique) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -38,38 +38,10 @@ Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution,
|
||||||
|
|
||||||
// Compute BayesTree
|
// Compute BayesTree
|
||||||
factorization_ = factorization;
|
factorization_ = factorization;
|
||||||
if(factorization_ == CHOLESKY) {
|
if(factorization_ == CHOLESKY)
|
||||||
bayesTree_ = *graph_.eliminateMultifrontal(boost::none, EliminatePreferCholesky);
|
bayesTree_ = *graph_.eliminateMultifrontal(boost::none, EliminatePreferCholesky);
|
||||||
std::cout<<"performing Cholesky"<<std::endl;
|
else if(factorization_ == QR)
|
||||||
}
|
|
||||||
else if(factorization_ == QR) {
|
|
||||||
bayesTree_ = *graph_.eliminateMultifrontal(boost::none, EliminateQR);
|
bayesTree_ = *graph_.eliminateMultifrontal(boost::none, EliminateQR);
|
||||||
std::cout<<"performing QR"<<std::endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution, const std::string& str) {
|
|
||||||
Factorization factorization;
|
|
||||||
if (str == "QR") factorization = QR;
|
|
||||||
else if (str == "CHOLESKY") factorization = CHOLESKY;
|
|
||||||
gttic(MarginalsConstructor);
|
|
||||||
|
|
||||||
// Linearize graph
|
|
||||||
graph_ = *graph.linearize(solution);
|
|
||||||
|
|
||||||
// Store values
|
|
||||||
values_ = solution;
|
|
||||||
|
|
||||||
// Compute BayesTree
|
|
||||||
factorization_ = factorization;
|
|
||||||
if(factorization_ == CHOLESKY) {
|
|
||||||
bayesTree_ = *graph_.eliminateMultifrontal(boost::none, EliminatePreferCholesky);
|
|
||||||
std::cout<<"performing Cholesky"<<std::endl;
|
|
||||||
}
|
|
||||||
else if(factorization_ == QR) {
|
|
||||||
bayesTree_ = *graph_.eliminateMultifrontal(boost::none, EliminateQR);
|
|
||||||
std::cout<<"performing QR"<<std::endl;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -171,24 +143,4 @@ void JointMarginal::print(const std::string& s, const KeyFormatter& formatter) c
|
||||||
cout << ". Use 'at' or 'operator()' to query matrix blocks." << endl;
|
cout << ". Use 'at' or 'operator()' to query matrix blocks." << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
Marginals::Factorization Marginals::factorizationTranslator(const std::string& str) const {
|
|
||||||
// std::string s = str; boost::algorithm::to_upper(s);
|
|
||||||
if (str == "QR") return Marginals::QR;
|
|
||||||
if (str == "CHOLESKY") return Marginals::CHOLESKY;
|
|
||||||
|
|
||||||
/* default is CHOLESKY */
|
|
||||||
return Marginals::CHOLESKY;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
std::string Marginals::factorizationTranslator(const Marginals::Factorization& value) const {
|
|
||||||
std::string s;
|
|
||||||
switch (value) {
|
|
||||||
case Marginals::QR: s = "QR"; break;
|
|
||||||
case Marginals::CHOLESKY: s = "CHOLESKY"; break;
|
|
||||||
default: s = "UNDEFINED"; break;
|
|
||||||
}
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
|
|
||||||
} /* namespace gtsam */
|
} /* namespace gtsam */
|
||||||
|
|
|
@ -54,7 +54,6 @@ public:
|
||||||
* @param factorization The linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).
|
* @param factorization The linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).
|
||||||
*/
|
*/
|
||||||
Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization = CHOLESKY);
|
Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization = CHOLESKY);
|
||||||
Marginals(const NonlinearFactorGraph& graph, const Values& solution, const std::string& str);
|
|
||||||
|
|
||||||
/** print */
|
/** print */
|
||||||
void print(const std::string& str = "Marginals: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
void print(const std::string& str = "Marginals: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
||||||
|
@ -72,16 +71,6 @@ public:
|
||||||
|
|
||||||
/** Compute the joint marginal information of several variables */
|
/** Compute the joint marginal information of several variables */
|
||||||
JointMarginal jointMarginalInformation(const std::vector<Key>& variables) const;
|
JointMarginal jointMarginalInformation(const std::vector<Key>& variables) const;
|
||||||
|
|
||||||
Factorization factorizationTranslator(const std::string& str) const;
|
|
||||||
|
|
||||||
std::string factorizationTranslator(const Marginals::Factorization& value) const;
|
|
||||||
|
|
||||||
void setFactorization(const std::string& factorization) { this->factorization_ = factorizationTranslator(factorization); }
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Reference in New Issue