Added instantiation macros for TupleConfigs and NonlinearConstraints

release/4.3a0
Alex Cunningham 2010-02-08 22:29:00 +00:00
parent fbef948254
commit 18d7fcc299
3 changed files with 50 additions and 3 deletions

View File

@ -10,6 +10,10 @@
#include <boost/bind.hpp>
#include "NonlinearConstraint.h"
#define INSTANTIATE_NONLINEAR_CONSTRAINT(C) \
INSTANTIATE_FACTOR_GRAPH(NonlinearConstraint<C>); \
template class NonlinearConstraint<C>;
namespace gtsam {
/* ************************************************************************* */

View File

@ -18,9 +18,27 @@
/*template void PairConfig<J1,X1,J2,X2>::print(const std::string&) const;*/ \
template PairConfig<J1,X1,J2,X2> expmap(PairConfig<J1,X1,J2,X2>, const VectorConfig&);
#define INSTANTIATE_TUPLE_CONFIG(CONFIG) \
template class CONFIG; \
template CONFIG expmap(CONFIG, const VectorConfig&);
// TupleConfig instantiations for N = 1-6
#define INSTANTIATE_TUPLE_CONFIG2(Config1, Config2) \
template class TupleConfig2<Config1, Config2>; \
template TupleConfig2<Config1, Config2> expmap(const TupleConfig2<Config1, Config2>, const VectorConfig&);
#define INSTANTIATE_TUPLE_CONFIG3(Config1, Config2, Config3) \
template class TupleConfig3<Config1, Config2, Config3>; \
template TupleConfig3<Config1, Config2, Config3> expmap(const TupleConfig3<Config1, Config2, Config3>, const VectorConfig&);
#define INSTANTIATE_TUPLE_CONFIG4(Config1, Config2, Config3, Config4) \
template class TupleConfig4<Config1, Config2, Config3, Config4>; \
template TupleConfig4<Config1, Config2, Config3, Config4> expmap(const TupleConfig4<Config1, Config2, Config3, Config4>, const VectorConfig&);
#define INSTANTIATE_TUPLE_CONFIG5(Config1, Config2, Config3, Config4, Config5) \
template class TupleConfig5<Config1, Config2, Config3, Config4, Config5>; \
template TupleConfig5<Config1, Config2, Config3, Config4, Config5> expmap(const TupleConfig5<Config1, Config2, Config3, Config4, Config5>, const VectorConfig&);
#define INSTANTIATE_TUPLE_CONFIG6(Config1, Config2, Config3, Config4, Config5, Config6) \
template class TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6>; \
template TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6> expmap(const TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6>, const VectorConfig&);
namespace gtsam {

View File

@ -210,6 +210,11 @@ namespace gtsam {
inline const Config2_t& second() const { return this->rest().config(); }
};
template<class Config1, class Config2>
TupleConfig2<Config1, Config2> exmap(const TupleConfig2<Config1, Config2> c, const VectorConfig& delta) {
return c.exmap(delta);
}
template<class Config1, class Config2, class Config3>
class TupleConfig3 : public TupleConfig<Config1, TupleConfig<Config2, TupleConfigEnd<Config3> > > {
public:
@ -229,6 +234,11 @@ namespace gtsam {
inline const Config3_t& third() const { return this->rest().rest().config(); }
};
template<class Config1, class Config2, class Config3>
TupleConfig3<Config1, Config2, Config3> exmap(const TupleConfig3<Config1, Config2, Config3> c, const VectorConfig& delta) {
return c.exmap(delta);
}
template<class Config1, class Config2, class Config3, class Config4>
class TupleConfig4 : public TupleConfig<Config1, TupleConfig<Config2,TupleConfig<Config3, TupleConfigEnd<Config4> > > > {
public:
@ -250,6 +260,11 @@ namespace gtsam {
inline const Config4_t& fourth() const { return this->rest().rest().rest().config(); }
};
template<class Config1, class Config2, class Config3, class Config4>
TupleConfig4<Config1, Config2, Config3, Config4> exmap(const TupleConfig4<Config1, Config2, Config3, Config4> c, const VectorConfig& delta) {
return c.exmap(delta);
}
template<class Config1, class Config2, class Config3, class Config4, class Config5>
class TupleConfig5 : public TupleConfig<Config1, TupleConfig<Config2, TupleConfig<Config3, TupleConfig<Config4, TupleConfigEnd<Config5> > > > > {
public:
@ -274,6 +289,11 @@ namespace gtsam {
inline const Config5_t& fifth() const { return this->rest().rest().rest().rest().config(); }
};
template<class Config1, class Config2, class Config3, class Config4, class Config5>
TupleConfig5<Config1, Config2, Config3, Config4, Config5> exmap(const TupleConfig5<Config1, Config2, Config3, Config4, Config5> c, const VectorConfig& delta) {
return c.exmap(delta);
}
template<class Config1, class Config2, class Config3, class Config4, class Config5, class Config6>
class TupleConfig6 : public TupleConfig<Config1, TupleConfig<Config2, TupleConfig<Config3, TupleConfig<Config4, TupleConfig<Config5, TupleConfigEnd<Config6> > > > > > {
public:
@ -299,6 +319,11 @@ namespace gtsam {
inline const Config6_t& sixth() const { return this->rest().rest().rest().rest().rest().config(); }
};
template<class Config1, class Config2, class Config3, class Config4, class Config5, class Config6>
TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6> exmap(const TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6> c, const VectorConfig& delta) {
return c.exmap(delta);
}
/**
* PairConfig: an alias for a pair of configs using TupleConfig2
* STILL IN TESTING - will soon replace PairConfig