map_values eliminated

release/4.3a0
kartik arcot 2023-01-19 11:22:52 -08:00
parent ccc5e3881b
commit 4b40e6e346
9 changed files with 40 additions and 45 deletions

View File

@ -17,7 +17,6 @@
* @author Christian Potthast
*/
#include <boost/range/adaptor/map.hpp>
#include <gtsam/linear/Errors.h>
#include <gtsam/linear/VectorValues.h>
@ -28,7 +27,7 @@ namespace gtsam {
/* ************************************************************************* */
Errors createErrors(const VectorValues& V) {
Errors result;
for (const Vector& e : V | boost::adaptors::map_values) {
for (const auto& [key, e] : V) {
result.push_back(e);
}
return result;

View File

@ -14,7 +14,6 @@
#include <gtsam/linear/NoiseModel.h>
#include <memory>
#include <boost/algorithm/string.hpp>
#include <boost/range/adaptor/map.hpp>
#include <iostream>
#include <vector>
@ -145,8 +144,9 @@ void BlockJacobiPreconditioner::build(
/* getting the block diagonals over the factors */
std::map<Key, Matrix> hessianMap =gfg.hessianBlockDiagonal();
for (const Matrix& hessian: hessianMap | boost::adaptors::map_values)
for (const auto& [key, hessian]: hessianMap) {
blocks.push_back(hessian);
}
/* if necessary, allocating the memory for cacheing the factorization results */
if ( nnz > bufferSize_ ) {

View File

@ -28,7 +28,6 @@ using namespace std;
namespace gtsam {
using boost::adaptors::transformed;
using boost::adaptors::map_values;
using boost::accumulate;
/* ************************************************************************ */
@ -129,8 +128,9 @@ namespace gtsam {
/* ************************************************************************ */
void VectorValues::setZero()
{
for(Vector& v: values_ | map_values)
v.setZero();
for(auto& [key, value] : *this) {
value.setZero();
}
}
/* ************************************************************************ */
@ -178,14 +178,15 @@ namespace gtsam {
Vector VectorValues::vector() const {
// Count dimensions
DenseIndex totalDim = 0;
for (const Vector& v : *this | map_values) totalDim += v.size();
for (const auto& [key, value] : *this)
totalDim += value.size();
// Copy vectors
Vector result(totalDim);
DenseIndex pos = 0;
for (const Vector& v : *this | map_values) {
result.segment(pos, v.size()) = v;
pos += v.size();
for (const auto& [key, value] : *this) {
result.segment(pos, value.size()) = value;
pos += value.size();
}
return result;
@ -196,7 +197,7 @@ namespace gtsam {
{
// Count dimensions
DenseIndex totalDim = 0;
for(size_t dim: keys | map_values)
for (const auto& [key, dim] : keys)
totalDim += dim;
Vector result(totalDim);
size_t j = 0;
@ -236,8 +237,6 @@ namespace gtsam {
if(this->size() != v.size())
throw invalid_argument("VectorValues::dot called with a VectorValues of different structure");
double result = 0.0;
typedef std::tuple<value_type, value_type> ValuePair;
using boost::adaptors::map_values;
auto this_it = this->begin();
auto v_it = v.begin();
for(; this_it != this->end(); ++this_it, ++v_it) {
@ -258,9 +257,9 @@ namespace gtsam {
/* ************************************************************************ */
double VectorValues::squaredNorm() const {
double sumSquares = 0.0;
using boost::adaptors::map_values;
for(const Vector& v: *this | map_values)
sumSquares += v.squaredNorm();
for(const auto& [key, value]: *this) {
sumSquares += value.squaredNorm();
}
return sumSquares;
}
@ -374,8 +373,9 @@ namespace gtsam {
/* ************************************************************************ */
VectorValues& VectorValues::operator*=(double alpha)
{
for(Vector& v: *this | map_values)
v *= alpha;
for (auto& [key, value]: *this) {
value *= alpha;
}
return *this;
}

View File

@ -229,8 +229,13 @@ typename Expression<T>::KeysAndDims Expression<T>::keysAndDims() const {
dims(map);
size_t n = map.size();
KeysAndDims pair = std::make_pair(KeyVector(n), FastVector<int>(n));
boost::copy(map | boost::adaptors::map_keys, pair.first.begin());
boost::copy(map | boost::adaptors::map_values, pair.second.begin());
// Copy map into pair of vectors
auto key_it = pair.first.begin();
auto dim_it = pair.second.begin();
for (const auto& [key, value] : map) {
*key_it++ = key;
*dim_it++ = value;
}
return pair;
}

View File

@ -29,7 +29,6 @@
#include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <boost/range/adaptor/map.hpp>
#include <cmath>
#include <fstream>
@ -41,7 +40,6 @@ using namespace std;
namespace gtsam {
using boost::adaptors::map_values;
typedef internal::LevenbergMarquardtState State;
/* ************************************************************************* */
@ -281,8 +279,8 @@ GaussianFactorGraph::shared_ptr LevenbergMarquardtOptimizer::iterate() {
VectorValues sqrtHessianDiagonal;
if (params_.diagonalDamping) {
sqrtHessianDiagonal = linear->hessianDiagonal();
for (Vector& v : sqrtHessianDiagonal | map_values) {
v = v.cwiseMax(params_.minDiagonal).cwiseMin(params_.maxDiagonal).cwiseSqrt();
for (auto& [key, value] : sqrtHessianDiagonal) {
value = value.cwiseMax(params_.minDiagonal).cwiseMin(params_.maxDiagonal).cwiseSqrt();
}
}

View File

@ -26,10 +26,6 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/tuple/tuple.hpp>
#include <boost/range/adaptor/map.hpp>
namespace br { using namespace boost::range; using namespace boost::adaptors; }
#include <string.h>
#include <iostream>
@ -450,7 +446,7 @@ TEST( GaussianFactorGraph, conditional_sigma_failure) {
GaussianBayesTree actBT = *lfg.eliminateMultifrontal();
// Check that all sigmas in an unconstrained bayes tree are set to one
for(const GaussianBayesTree::sharedClique& clique: actBT.nodes() | br::map_values) {
for (const auto& [key, clique]: actBT.nodes()) {
GaussianConditional::shared_ptr conditional = clique->conditional();
//size_t dim = conditional->rows();
//EXPECT(assert_equal(gtsam::Vector::Ones(dim), conditional->get_model()->sigmas(), tol));

View File

@ -22,9 +22,6 @@
#include <gtsam/linear/GaussianISAM.h>
#include <gtsam/inference/Ordering.h>
#include <boost/range/adaptor/map.hpp>
namespace br { using namespace boost::adaptors; using namespace boost::range; }
using namespace std;
using namespace gtsam;
using namespace example;
@ -53,7 +50,7 @@ TEST( ISAM, iSAM_smoother )
GaussianBayesTree expected = *smoother.eliminateMultifrontal(ordering);
// Verify sigmas in the bayes tree
for(const GaussianBayesTree::sharedClique& clique: expected.nodes() | br::map_values) {
for (const auto& [key, clique] : expected.nodes()) {
GaussianConditional::shared_ptr conditional = clique->conditional();
EXPECT(!conditional->get_model());
}

View File

@ -24,8 +24,6 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/range/adaptor/map.hpp>
namespace br { using namespace boost::adaptors; using namespace boost::range; }
using namespace std;
using namespace gtsam;
@ -249,7 +247,7 @@ bool isam_check(const NonlinearFactorGraph& fullgraph, const Values& fullinit, c
// Check gradient at each node
bool nodeGradientsOk = true;
typedef ISAM2::sharedClique sharedClique;
for(const sharedClique& clique: isam.nodes() | br::map_values) {
for (const auto& [key, clique] : isam.nodes()) {
// Compute expected gradient
GaussianFactorGraph jfg;
jfg += clique->conditional();
@ -453,7 +451,7 @@ TEST(ISAM2, swapFactors)
// Check gradient at each node
typedef ISAM2::sharedClique sharedClique;
for(const sharedClique& clique: isam.nodes() | br::map_values) {
for (const auto& [key, clique]: isam.nodes()) {
// Compute expected gradient
GaussianFactorGraph jfg;
jfg += clique->conditional();
@ -578,7 +576,7 @@ TEST(ISAM2, constrained_ordering)
// Check gradient at each node
typedef ISAM2::sharedClique sharedClique;
for(const sharedClique& clique: isam.nodes() | br::map_values) {
for (const auto& [key, clique]: isam.nodes()) {
// Compute expected gradient
GaussianFactorGraph jfg;
jfg += clique->conditional();
@ -620,9 +618,11 @@ namespace {
bool checkMarginalizeLeaves(ISAM2& isam, const FastList<Key>& leafKeys) {
Matrix expectedAugmentedHessian, expected3AugmentedHessian;
KeyVector toKeep;
for(Key j: isam.getDelta() | br::map_keys)
if(find(leafKeys.begin(), leafKeys.end(), j) == leafKeys.end())
toKeep.push_back(j);
for (const auto& [key, clique]: isam.getDelta()) {
if(find(leafKeys.begin(), leafKeys.end(), key) == leafKeys.end()) {
toKeep.push_back(key);
}
}
// Calculate expected marginal from iSAM2 tree
expectedAugmentedHessian = GaussianFactorGraph(isam).marginal(toKeep, EliminateQR)->augmentedHessian();

View File

@ -31,8 +31,6 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/range/adaptor/map.hpp>
using boost::adaptors::map_values;
#include <iostream>
#include <fstream>
@ -302,7 +300,9 @@ TEST_UNSAFE(NonlinearOptimizer, MoreOptimization) {
GaussianFactorGraph::shared_ptr linear = optimizer.linearize();
VectorValues d = linear->hessianDiagonal();
VectorValues sqrtHessianDiagonal = d;
for (Vector& v : sqrtHessianDiagonal | map_values) v = v.cwiseSqrt();
for (auto& [key, value] : sqrtHessianDiagonal) {
value = value.cwiseSqrt();
}
GaussianFactorGraph damped = optimizer.buildDampedSystem(*linear, sqrtHessianDiagonal);
VectorValues expectedDiagonal = d + params.lambdaInitial * d;
EXPECT(assert_equal(expectedDiagonal, damped.hessianDiagonal()));