/** * @file FusionTupleConfig.h * @brief Experimental tuple config using boost.Fusion * @author Alex Cunningham */ #pragma once #include #include #include #include #include #include #include #include #include #include #include #include #include "Testable.h" #include "LieConfig.h" namespace gtsam { /** * This config uses a real tuple to store types * The template parameter should be a boost fusion structure, like * set */ template class FusionTupleConfig : public Testable >{ public: /** useful types */ typedef Configs BaseTuple; protected: /** the underlying tuple storing everything */ Configs base_tuple_; public: /** create an empty config */ FusionTupleConfig() {} /** copy constructor */ FusionTupleConfig(const FusionTupleConfig& other) : base_tuple_(other.base_tuple_) {} /** direct initialization of the underlying structure */ FusionTupleConfig(const Configs& cfg_set) : base_tuple_(cfg_set) {} /** initialization from arbitrary other configs */ template FusionTupleConfig(const FusionTupleConfig& other) : base_tuple_(boost::fusion::fold(other.base_tuple(), Configs(), assign_outer())) { } virtual ~FusionTupleConfig() {} /** insertion */ template void insert(const Key& j, const Value& x) { boost::fusion::at_key >(base_tuple_).insert(j,x); } /** retrieve a point */ template const typename Key::Value_t & at(const Key& j) const { return boost::fusion::at_key >(base_tuple_).at(j); } /** retrieve a full config */ template const Config & config() const { return boost::fusion::at_key(base_tuple_); } /** size of the config - sum all sizes from subconfigs */ size_t size() const { return boost::fusion::accumulate(base_tuple_, 0, FusionTupleConfig::size_helper()); } /** number of configs in the config */ size_t nrConfigs() const { return boost::fusion::size(base_tuple_); } /** returns true if the config is empty */ bool empty() const { return boost::fusion::all(base_tuple_, FusionTupleConfig::empty_helper()); } /** print */ void print(const std::string& s="") const { std::cout << "FusionTupleConfig " << s << ":" << std::endl; boost::fusion::for_each(base_tuple_, FusionTupleConfig::print_helper()); } /** equals */ bool equals(const FusionTupleConfig& other, double tol=1e-9) const { FusionTupleConfig::equals_helper helper(tol); return boost::fusion::all( boost::fusion::zip( boost::fusion::as_vector(base_tuple_), boost::fusion::as_vector(other.base_tuple_)), helper); } /** direct access to the underlying fusion set - don't use this */ const BaseTuple & base_tuple() const { return base_tuple_; } private: /** helper structs to make use of fusion algorithms */ struct size_helper { typedef size_t result_type; template size_t operator()(const T& t, const size_t& s) const { return s + t.size(); } }; struct empty_helper { template bool operator()(T t) const { return t.empty(); } }; struct print_helper { template void operator()(T t) const { t.print(); } }; struct equals_helper { double tol; equals_helper(double t) : tol(t) {} template bool operator()(T t) const { return boost::fusion::at_c<0>(t).equals(boost::fusion::at_c<1>(t), tol); } }; /** two separate function objects for arbitrary copy construction */ template struct assign_inner { typedef Ret result_type; Config config; assign_inner(const Config& cfg) : config(cfg) {} template result_type operator()(const T& t, const result_type& s) const { result_type new_s(s); T new_cfg(config); if (!new_cfg.empty()) boost::fusion::at_key(new_s) = new_cfg; return new_s; } }; template struct assign_outer { typedef Ret result_type; template // T is the config from the "other" config Ret operator()(const T& t, const Ret& s) const { assign_inner helper(t); return boost::fusion::fold(s, s, helper); // loop over the "self" config } }; }; } // \namespace gtsam