/** * @file LieValues.cpp * @author Richard Roberts */ #pragma once #include #include #include #include #include #include #include #include #include #include #define INSTANTIATE_LIE_CONFIG(J) \ /*INSTANTIATE_LIE(T);*/ \ /*template LieValues expmap(const LieValues&, const VectorValues&);*/ \ /*template LieValues expmap(const LieValues&, const Vector&);*/ \ /*template VectorValues logmap(const LieValues&, const LieValues&);*/ \ template class LieValues; using namespace std; namespace gtsam { /* ************************************************************************* */ template void LieValues::print(const string &s) const { cout << "LieValues " << s << ", size " << values_.size() << "\n"; BOOST_FOREACH(const KeyValuePair& v, values_) { gtsam::print(v.second, (string)(v.first)); } } /* ************************************************************************* */ template bool LieValues::equals(const LieValues& 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& LieValues::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 LieValues::dim() const { size_t n = 0; BOOST_FOREACH(const KeyValuePair& value, values_) n += value.second.dim(); return n; } /* ************************************************************************* */ template VectorValues LieValues::zero(const Ordering& ordering) const { VectorValues z(this->dims(ordering)); z.makeZero(); return z; } /* ************************************************************************* */ template void LieValues::insert(const J& name, const typename J::Value& val) { values_.insert(make_pair(name, val)); } /* ************************************************************************* */ template void LieValues::insert(const LieValues& cfg) { BOOST_FOREACH(const KeyValuePair& v, cfg.values_) insert(v.first, v.second); } /* ************************************************************************* */ template void LieValues::update(const LieValues& cfg) { BOOST_FOREACH(const KeyValuePair& v, values_) { boost::optional t = cfg.exists_(v.first); if (t) values_[v.first] = *t; } } /* ************************************************************************* */ template void LieValues::update(const J& j, const typename J::Value& val) { values_[j] = val; } /* ************************************************************************* */ template std::list LieValues::keys() const { std::list ret; BOOST_FOREACH(const KeyValuePair& v, values_) ret.push_back(v.first); return ret; } /* ************************************************************************* */ template void LieValues::erase(const J& j) { size_t dim; // unused erase(j, dim); } /* ************************************************************************* */ template void LieValues::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 LieValues LieValues::expmap(const VectorValues& delta, const Ordering& ordering) const { LieValues newValues; typedef pair KeyValue; BOOST_FOREACH(const KeyValue& value, this->values_) { const J& j = value.first; const typename J::Value& pj = value.second; const Vector& dj = delta[ordering[j]]; newValues.insert(j, pj.expmap(dj)); } return newValues; } /* ************************************************************************* */ template std::vector LieValues::dims(const Ordering& ordering) const { _ValuesDimensionCollector dimCollector(ordering); this->apply(dimCollector); return dimCollector.dimensions; } /* ************************************************************************* */ template Ordering::shared_ptr LieValues::orderingArbitrary(varid_t firstVar) const { // Generate an initial key ordering in iterator order _ValuesKeyOrderer keyOrderer(firstVar); this->apply(keyOrderer); return keyOrderer.ordering; } // /* ************************************************************************* */ // // todo: insert for every element is inefficient // template // LieValues LieValues::expmap(const Vector& delta) const { // if(delta.size() != dim()) { // cout << "LieValues::dim (" << dim() << ") <> delta.size (" << delta.size() << ")" << endl; // throw invalid_argument("Delta vector length does not match config dimensionality."); // } // LieValues newValues; // int delta_offset = 0; // typedef pair KeyValue; // BOOST_FOREACH(const KeyValue& value, this->values_) { // const J& j = value.first; // const typename J::Value& pj = value.second; // int cur_dim = pj.dim(); // newValues.insert(j,pj.expmap(sub(delta, delta_offset, delta_offset+cur_dim))); // delta_offset += cur_dim; // } // return newValues; // } /* ************************************************************************* */ // todo: insert for every element is inefficient // todo: currently only logmaps elements in both configs template inline VectorValues LieValues::logmap(const LieValues& cp, const Ordering& ordering) const { VectorValues delta(this->dims(ordering)); logmap(cp, ordering, delta); return delta; } /* ************************************************************************* */ template void LieValues::logmap(const LieValues& cp, const Ordering& ordering, VectorValues& delta) const { typedef pair KeyValue; BOOST_FOREACH(const KeyValue& value, cp) { assert(this->exists(value.first)); delta[ordering[value.first]] = this->at(value.first).logmap(value.second); } } }