Removed unused TupleConfigEnd global expmap and logmap as they were causing function resolution problems

release/4.3a0
Richard Roberts 2010-03-10 16:30:00 +00:00
parent d149afbec2
commit cf28e3ab04
2 changed files with 10 additions and 20 deletions

View File

@ -16,7 +16,7 @@
/*INSTANTIATE_LIE_CONFIG(J2,X2);*/ \ /*INSTANTIATE_LIE_CONFIG(J2,X2);*/ \
template class PairConfig<J1,X1,J2,X2>; \ template class PairConfig<J1,X1,J2,X2>; \
/*template void PairConfig<J1,X1,J2,X2>::print(const std::string&) const;*/ \ /*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&); template PairConfig<J1,X1,J2,X2> expmap(const PairConfig<J1,X1,J2,X2>&, const VectorConfig&);
// TupleConfig instantiations for N = 1-6 // TupleConfig instantiations for N = 1-6
#define INSTANTIATE_TUPLE_CONFIG2(Config1, Config2) \ #define INSTANTIATE_TUPLE_CONFIG2(Config1, Config2) \

View File

@ -177,23 +177,13 @@ namespace gtsam {
/** Exmap static functions */ /** Exmap static functions */
template<class Config1, class Config2> template<class Config1, class Config2>
inline TupleConfig<Config1, Config2> expmap(const TupleConfig<Config1, Config2> c, const VectorConfig& delta) { inline TupleConfig<Config1, Config2> expmap(const TupleConfig<Config1, Config2>& c, const VectorConfig& delta) {
return c.expmap(delta);
}
template<class Config>
inline TupleConfigEnd<Config> expmap(const TupleConfigEnd<Config> c, const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
/** logmap static functions */ /** logmap static functions */
template<class Config1, class Config2> template<class Config1, class Config2>
inline VectorConfig logmap(const TupleConfig<Config1, Config2> c0, const TupleConfig<Config1, Config2>& cp) { inline VectorConfig logmap(const TupleConfig<Config1, Config2>& c0, const TupleConfig<Config1, Config2>& cp) {
return c0.logmap(cp);
}
template<class Config>
inline VectorConfig logmap(const TupleConfigEnd<Config> c0, const TupleConfigEnd<Config>& cp) {
return c0.logmap(cp); return c0.logmap(cp);
} }
@ -225,7 +215,7 @@ namespace gtsam {
}; };
template<class Config1, class Config2> template<class Config1, class Config2>
TupleConfig2<Config1, Config2> expmap(const TupleConfig2<Config1, Config2> c, const VectorConfig& delta) { TupleConfig2<Config1, Config2> expmap(const TupleConfig2<Config1, Config2>& c, const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
@ -249,7 +239,7 @@ namespace gtsam {
}; };
template<class Config1, class Config2, class Config3> template<class Config1, class Config2, class Config3>
TupleConfig3<Config1, Config2, Config3> expmap(const TupleConfig3<Config1, Config2, Config3> c, const VectorConfig& delta) { TupleConfig3<Config1, Config2, Config3> expmap(const TupleConfig3<Config1, Config2, Config3>& c, const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
@ -278,7 +268,7 @@ namespace gtsam {
}; };
template<class Config1, class Config2, class Config3, class Config4> template<class Config1, class Config2, class Config3, class Config4>
TupleConfig4<Config1, Config2, Config3, Config4> expmap(const TupleConfig4<Config1, Config2, Config3, Config4> c, const VectorConfig& delta) { TupleConfig4<Config1, Config2, Config3, Config4> expmap(const TupleConfig4<Config1, Config2, Config3, Config4>& c, const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
@ -307,7 +297,7 @@ namespace gtsam {
}; };
template<class Config1, class Config2, class Config3, class Config4, class Config5> template<class Config1, class Config2, class Config3, class Config4, class Config5>
TupleConfig5<Config1, Config2, Config3, Config4, Config5> expmap(const TupleConfig5<Config1, Config2, Config3, Config4, Config5> c, const VectorConfig& delta) { TupleConfig5<Config1, Config2, Config3, Config4, Config5> expmap(const TupleConfig5<Config1, Config2, Config3, Config4, Config5>& c, const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
@ -337,7 +327,7 @@ namespace gtsam {
}; };
template<class Config1, class Config2, class Config3, class Config4, class Config5, class Config6> template<class Config1, class Config2, class Config3, class Config4, class Config5, class Config6>
TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6> expmap(const TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6> c, const VectorConfig& delta) { TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6> expmap(const TupleConfig6<Config1, Config2, Config3, Config4, Config5, Config6>& c, const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
@ -487,14 +477,14 @@ namespace gtsam {
/** exponential map */ /** exponential map */
template<class J1, class X1, class J2, class X2> template<class J1, class X1, class J2, class X2>
inline PairConfig<J1, X1, J2, X2> expmap(const PairConfig<J1, X1, J2, X2> c, inline PairConfig<J1, X1, J2, X2> expmap(const PairConfig<J1, X1, J2, X2>& c,
const VectorConfig& delta) { const VectorConfig& delta) {
return c.expmap(delta); return c.expmap(delta);
} }
/** log, inverse of exponential map */ /** log, inverse of exponential map */
template<class J1, class X1, class J2, class X2> template<class J1, class X1, class J2, class X2>
inline VectorConfig logmap(const PairConfig<J1, X1, J2, X2> c0, inline VectorConfig logmap(const PairConfig<J1, X1, J2, X2>& c0,
const PairConfig<J1, X1, J2, X2>& cp) { const PairConfig<J1, X1, J2, X2>& cp) {
return c0.logmap(cp); return c0.logmap(cp);
} }