Fixed references to "CONFIG" in instantiation macros
parent
3e1761b81b
commit
d9fea3946a
|
|
@ -29,7 +29,7 @@
|
|||
|
||||
#include <gtsam/nonlinear/LieValues.h>
|
||||
|
||||
#define INSTANTIATE_LIE_CONFIG(J) \
|
||||
#define INSTANTIATE_LIE_VALUES(J) \
|
||||
/*INSTANTIATE_LIE(T);*/ \
|
||||
/*template LieValues<J> expmap(const LieValues<J>&, const VectorValues&);*/ \
|
||||
/*template LieValues<J> expmap(const LieValues<J>&, const Vector&);*/ \
|
||||
|
|
|
|||
|
|
@ -22,22 +22,22 @@
|
|||
#include <gtsam/nonlinear/TupleValues.h>
|
||||
|
||||
// TupleValues instantiations for N = 1-6
|
||||
#define INSTANTIATE_TUPLE_CONFIG1(Values1) \
|
||||
#define INSTANTIATE_TUPLE_VALUES1(Values1) \
|
||||
template class TupleValues1<Values1>;
|
||||
|
||||
#define INSTANTIATE_TUPLE_CONFIG2(Values1, Values2) \
|
||||
#define INSTANTIATE_TUPLE_VALUES2(Values1, Values2) \
|
||||
template class TupleValues2<Values1, Values2>;
|
||||
|
||||
#define INSTANTIATE_TUPLE_CONFIG3(Values1, Values2, Values3) \
|
||||
#define INSTANTIATE_TUPLE_VALUES3(Values1, Values2, Values3) \
|
||||
template class TupleValues3<Values1, Values2, Values3>;
|
||||
|
||||
#define INSTANTIATE_TUPLE_CONFIG4(Values1, Values2, Values3, Values4) \
|
||||
#define INSTANTIATE_TUPLE_VALUES4(Values1, Values2, Values3, Values4) \
|
||||
template class TupleValues4<Values1, Values2, Values3, Values4>;
|
||||
|
||||
#define INSTANTIATE_TUPLE_CONFIG5(Values1, Values2, Values3, Values4, Values5) \
|
||||
#define INSTANTIATE_TUPLE_VALUES5(Values1, Values2, Values3, Values4, Values5) \
|
||||
template class TupleValues5<Values1, Values2, Values3, Values4, Values5>;
|
||||
|
||||
#define INSTANTIATE_TUPLE_CONFIG6(Values1, Values2, Values3, Values4, Values5, Values6) \
|
||||
#define INSTANTIATE_TUPLE_VALUES6(Values1, Values2, Values3, Values4, Values5, Values6) \
|
||||
template class TupleValues6<Values1, Values2, Values3, Values4, Values5, Values6>;
|
||||
|
||||
|
||||
|
|
|
|||
|
|
@ -22,9 +22,9 @@
|
|||
namespace gtsam {
|
||||
|
||||
using namespace simulated3D;
|
||||
INSTANTIATE_LIE_CONFIG(PointKey)
|
||||
INSTANTIATE_LIE_CONFIG(PoseKey)
|
||||
INSTANTIATE_TUPLE_CONFIG2(PoseValues, PointValues)
|
||||
INSTANTIATE_LIE_VALUES(PointKey)
|
||||
INSTANTIATE_LIE_VALUES(PoseKey)
|
||||
INSTANTIATE_TUPLE_VALUES2(PoseValues, PointValues)
|
||||
|
||||
namespace simulated3D {
|
||||
|
||||
|
|
|
|||
|
|
@ -24,8 +24,8 @@
|
|||
namespace gtsam {
|
||||
|
||||
using namespace planarSLAM;
|
||||
INSTANTIATE_LIE_CONFIG(PointKey)
|
||||
INSTANTIATE_TUPLE_CONFIG2(PoseValues, PointValues)
|
||||
INSTANTIATE_LIE_VALUES(PointKey)
|
||||
INSTANTIATE_TUPLE_VALUES2(PoseValues, PointValues)
|
||||
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(Values)
|
||||
INSTANTIATE_NONLINEAR_OPTIMIZER(Graph, Values)
|
||||
|
||||
|
|
|
|||
|
|
@ -24,7 +24,7 @@
|
|||
namespace gtsam {
|
||||
|
||||
using namespace pose2SLAM;
|
||||
INSTANTIATE_LIE_CONFIG(Key)
|
||||
INSTANTIATE_LIE_VALUES(Key)
|
||||
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(Values)
|
||||
INSTANTIATE_NONLINEAR_OPTIMIZER(Graph, Values)
|
||||
template class NonlinearOptimizer<Graph, Values, GaussianFactorGraph, GaussianSequentialSolver>;
|
||||
|
|
|
|||
|
|
@ -24,7 +24,7 @@
|
|||
namespace gtsam {
|
||||
|
||||
using namespace pose3SLAM;
|
||||
INSTANTIATE_LIE_CONFIG(Key)
|
||||
INSTANTIATE_LIE_VALUES(Key)
|
||||
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(Values)
|
||||
INSTANTIATE_NONLINEAR_OPTIMIZER(Graph, Values)
|
||||
|
||||
|
|
|
|||
|
|
@ -28,7 +28,7 @@ using namespace std;
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
INSTANTIATE_LIE_CONFIG(Symbol, Point2)
|
||||
INSTANTIATE_LIE_VALUES(Symbol, Point2)
|
||||
|
||||
/* ************************************************************************* */
|
||||
void saveGraph(const SymbolicFactorGraph& fg, const SymbolicValues& config, const std::string& s) {
|
||||
|
|
|
|||
|
|
@ -23,8 +23,8 @@ namespace gtsam {
|
|||
|
||||
using namespace simulated2D;
|
||||
|
||||
INSTANTIATE_LIE_CONFIG(PoseKey)
|
||||
INSTANTIATE_TUPLE_CONFIG2(PoseValues, PointValues)
|
||||
INSTANTIATE_LIE_VALUES(PoseKey)
|
||||
INSTANTIATE_TUPLE_VALUES2(PoseValues, PointValues)
|
||||
|
||||
namespace simulated2D {
|
||||
|
||||
|
|
|
|||
|
|
@ -22,7 +22,7 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
|
||||
|
||||
namespace gtsam {
|
||||
INSTANTIATE_TUPLE_CONFIG2(visualSLAM::PoseValues, visualSLAM::PointValues)
|
||||
INSTANTIATE_TUPLE_VALUES2(visualSLAM::PoseValues, visualSLAM::PointValues)
|
||||
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(visualSLAM::Values)
|
||||
INSTANTIATE_NONLINEAR_OPTIMIZER(visualSLAM::Graph, visualSLAM::Values)
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue