/* * LieConfig.cpp * * Created on: Jan 8, 2010 * Author: richard */ #include #include #include #include #include #include "VectorConfig.h" #include "Lie-inl.h" #include "LieConfig.h" #define INSTANTIATE_LIE_CONFIG(J,T) \ /*INSTANTIATE_LIE(T);*/ \ template LieConfig expmap(const LieConfig&, const VectorConfig&); \ template LieConfig expmap(const LieConfig&, const Vector&); \ template VectorConfig logmap(const LieConfig&, const LieConfig&); \ template class LieConfig; 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 J& j) const { const_iterator it = values_.find(j); if (it == values_.end()) throw std::invalid_argument("invalid j: " + (string)j); else return it->second; } template void LieConfig::insert(const J& name, const T& val) { values_.insert(make_pair(name, val)); dim_ += gtsam::dim(val); } template void LieConfig::erase(const J& j) { size_t dim; // unused erase(j, dim); } template void LieConfig::erase(const J& j, size_t& dim) { iterator it = values_.find(j); if (it == values_.end()) throw std::invalid_argument("invalid j: " + (string)j); dim = gtsam::dim(it->second); dim_ -= dim; values_.erase(it); } // todo: insert for every element is inefficient template LieConfig expmap(const LieConfig& c, const VectorConfig& delta) { LieConfig newConfig; typedef pair Value; BOOST_FOREACH(const Value& value, c) { const J& j = value.first; const T& pj = value.second; Symbol jkey = (Symbol)j; if (delta.contains(jkey)) { const Vector& dj = delta[jkey]; 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 Value; BOOST_FOREACH(const Value& value, c) { const J& 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; } // todo: insert for every element is inefficient // todo: currently only logmaps elements in both configs template VectorConfig logmap(const LieConfig& c0, const LieConfig& cp) { VectorConfig delta; typedef pair Value; BOOST_FOREACH(const Value& value, cp) { if(c0.exists(value.first)) delta.insert(value.first, logmap(c0[value.first], value.second)); } return delta; } }