/** * @file LieConfig.cpp * @author Richard Roberts */ #pragma once #include #include #include #include #include #include #include #include #include #define INSTANTIATE_LIE_CONFIG(J) \ /*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 KeyValuePair& 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 KeyValuePair& v, values_) { if (!expected.exists(v.first)) return false; if(!gtsam::equal(v.second, expected[v.first], tol)) return false; } return true; } /* ************************************************************************* */ template const typename J::Value_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 size_t LieConfig::dim() const { size_t n = 0; BOOST_FOREACH(const KeyValuePair& value, values_) n += value.second.dim(); return n; } /* ************************************************************************* */ template VectorConfig LieConfig::zero() const { VectorConfig z; BOOST_FOREACH(const KeyValuePair& value, values_) z.insert(value.first,gtsam::zero(value.second.dim())); return z; } /* ************************************************************************* */ template void LieConfig::insert(const J& name, const typename J::Value_t& val) { values_.insert(make_pair(name, val)); } /* ************************************************************************* */ template void LieConfig::insert(const LieConfig& cfg) { BOOST_FOREACH(const KeyValuePair& v, cfg.values_) insert(v.first, v.second); } /* ************************************************************************* */ template void LieConfig::update(const LieConfig& cfg) { BOOST_FOREACH(const KeyValuePair& v, values_) { boost::optional t = cfg.exists_(v.first); if (t) values_[v.first] = *t; } } /* ************************************************************************* */ template void LieConfig::update(const J& j, const typename J::Value_t& val) { values_[j] = val; } /* ************************************************************************* */ template std::list LieConfig::keys() const { std::list ret; BOOST_FOREACH(const KeyValuePair& v, values_) ret.push_back(v.first); return ret; } /* ************************************************************************* */ 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 = it->second.dim(); values_.erase(it); } /* ************************************************************************* */ // todo: insert for every element is inefficient template LieConfig LieConfig::expmap(const VectorConfig& delta) const { LieConfig newConfig; typedef pair KeyValue; BOOST_FOREACH(const KeyValue& value, this->values_) { const J& j = value.first; const typename J::Value_t& pj = value.second; Symbol jkey = (Symbol)j; if (delta.contains(jkey)) { const Vector& dj = delta[jkey]; newConfig.insert(j, pj.expmap(dj)); } else newConfig.insert(j, pj); } return newConfig; } /* ************************************************************************* */ // todo: insert for every element is inefficient template LieConfig LieConfig::expmap(const Vector& delta) const { if(delta.size() != dim()) { cout << "LieConfig::dim (" << dim() << ") <> delta.size (" << delta.size() << ")" << endl; throw invalid_argument("Delta vector length does not match config dimensionality."); } LieConfig newConfig; int delta_offset = 0; typedef pair KeyValue; BOOST_FOREACH(const KeyValue& value, this->values_) { const J& j = value.first; const typename J::Value_t& pj = value.second; int cur_dim = pj.dim(); newConfig.insert(j,pj.expmap(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 LieConfig::logmap(const LieConfig& cp) const { VectorConfig delta; typedef pair KeyValue; BOOST_FOREACH(const KeyValue& value, cp) { if(this->exists(value.first)) delta.insert(value.first, this->at(value.first).logmap(value.second)); } return delta; } }