/* * LieConfig.cpp * * Created on: Jan 8, 2010 * Author: richard */ #include "LieConfig.h" #include #include #include #include #include #include "VectorConfig.h" using namespace std; namespace gtsam { template void LieConfig::print(const string &s) const { cout << "LieConfig " << s << ", size " << values_.size() << "\n"; BOOST_FOREACH(const typename Values::value_type& v, values_) gtsam::print(v.second, (string)(v.first)); } template bool LieConfig::equals(const LieConfig& expected, double tol) const { if (values_.size() != expected.values_.size()) return false; BOOST_FOREACH(const typename Values::value_type& v, values_) { if (!exists(v.first)) return false; if(!gtsam::equal(v.second, expected[v.first], tol)) return false; } return true; } template const T& LieConfig::at(const Key& key) const { const_iterator it = values_.find(key); if (it == values_.end()) throw std::invalid_argument("invalid key: " + (string)key); else return it->second; } template void LieConfig::insert(const Key& name, const T& val) { values_.insert(make_pair(name, val)); dim_ += dim(val); } template void LieConfig::erase(const Key& key) { iterator it = values_.find(key); if (it == values_.end()) throw std::invalid_argument("invalid key: " + (string)key); values_.erase(it); } // todo: insert for every element is inefficient template LieConfig expmap(const LieConfig& c, const VectorConfig& delta) { LieConfig newConfig; typedef pair::Key,T> Value; BOOST_FOREACH(const Value& value, c) { const typename LieConfig::Key& j = value.first; const T& pj = value.second; string key = (string)j; if (delta.contains(key)) { const Vector& dj = delta[key]; newConfig.insert(j, expmap(pj,dj)); } else newConfig.insert(j, pj); } return newConfig; } // todo: insert for every element is inefficient template LieConfig expmap(const LieConfig& c, const Vector& delta) { if(delta.size() != dim(c)) throw invalid_argument("Delta vector length does not match config dimensionality."); LieConfig newConfig; int delta_offset = 0; typedef pair::Key,T> Value; BOOST_FOREACH(const Value& value, c) { const typename LieConfig::Key& j = value.first; const T& pj = value.second; int cur_dim = dim(pj); newConfig.insert(j,expmap(pj,sub(delta, delta_offset, delta_offset+cur_dim))); delta_offset += cur_dim; } return newConfig; } }