diff --git a/examples/vSLAMexample/vISAMexample.cpp b/examples/vSLAMexample/vISAMexample.cpp index ae26a9c47..71d5516a2 100644 --- a/examples/vSLAMexample/vISAMexample.cpp +++ b/examples/vSLAMexample/vISAMexample.cpp @@ -20,9 +20,6 @@ #include using namespace boost; -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/examples/vSLAMexample/vSFMexample.cpp b/examples/vSLAMexample/vSFMexample.cpp index 468620f29..c7e0df05c 100644 --- a/examples/vSLAMexample/vSFMexample.cpp +++ b/examples/vSLAMexample/vSFMexample.cpp @@ -19,9 +19,6 @@ #include using namespace boost; -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/gtsam/inference/tests/testFactorGraph.cpp b/gtsam/inference/tests/testFactorGraph.cpp index 641b1f4f9..8669329bb 100644 --- a/gtsam/inference/tests/testFactorGraph.cpp +++ b/gtsam/inference/tests/testFactorGraph.cpp @@ -25,9 +25,6 @@ using namespace boost::assign; #include -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include using namespace std; diff --git a/gtsam/inference/tests/testISAM.cpp b/gtsam/inference/tests/testISAM.cpp index 1c6a2897c..acb849b8b 100644 --- a/gtsam/inference/tests/testISAM.cpp +++ b/gtsam/inference/tests/testISAM.cpp @@ -21,9 +21,6 @@ using namespace boost::assign; #include -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/gtsam/nonlinear/Symbol.h b/gtsam/nonlinear/Symbol.h index 854e18203..79d6a049b 100644 --- a/gtsam/nonlinear/Symbol.h +++ b/gtsam/nonlinear/Symbol.h @@ -23,14 +23,9 @@ #include #include #include -#ifdef GTSAM_MAGIC_KEY -#include -#endif #include -#define ALPHA '\224' - namespace gtsam { /** @@ -60,35 +55,6 @@ public: c_(c), j_(j) { } - /** "Magic" key casting constructor from string */ -#ifdef GTSAM_MAGIC_KEY - Symbol(const std::string& str) { - if(str.length() < 1) - throw std::invalid_argument("Cannot parse string key '" + str + "'"); - else { - const char *c_str = str.c_str(); - c_ = c_str[0]; - if(str.length() > 1) - j_ = boost::lexical_cast(c_str+1); - else - j_ = 0; - } - } - - Symbol(const char *c_str) { - std::string str(c_str); - if(str.length() < 1) - throw std::invalid_argument("Cannot parse string key '" + str + "'"); - else { - c_ = c_str[0]; - if(str.length() > 1) - j_ = boost::lexical_cast(c_str+1); - else - j_ = 0; - } - } -#endif - /** Constructor that decodes an integer Key */ Symbol(Key key) { const size_t keyBytes = sizeof(Key); diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index fac527dec..55854b339 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -20,8 +20,6 @@ #include // for operator += using namespace boost::assign; -#define GTSAM_MAGIC_KEY - #include #include #include @@ -33,7 +31,7 @@ using namespace gtsam; using namespace std; static double inf = std::numeric_limits::infinity(); -Key key1(Symbol("v1")), key2(Symbol("v2")), key3(Symbol("v3")), key4(Symbol("v4")); +Key key1(Symbol('v',1)), key2(Symbol('v',2)), key3(Symbol('v',3)), key4(Symbol('v',4)); /* ************************************************************************* */ TEST( Values, equals1 ) diff --git a/gtsam/slam/smallExample.cpp b/gtsam/slam/smallExample.cpp index f48d363b5..170f3ef03 100644 --- a/gtsam/slam/smallExample.cpp +++ b/gtsam/slam/smallExample.cpp @@ -24,9 +24,6 @@ using namespace std; -// Magically casts strings like Symbol("x3") to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include @@ -52,6 +49,9 @@ namespace example { static const Index _l1_=0, _x1_=1, _x2_=2; static const Index _x_=0, _y_=1, _z_=2; + Key kx(size_t i) { return Symbol('x',i); } + Key kl(size_t i) { return Symbol('l',i); } + /* ************************************************************************* */ boost::shared_ptr sharedNonlinearFactorGraph() { // Create @@ -121,18 +121,18 @@ namespace example { /* ************************************************************************* */ VectorValues createCorrectDelta(const Ordering& ordering) { VectorValues c(vector(3,2)); - c[ordering[Symbol(Symbol("l1"))]] = Vector_(2, -0.1, 0.1); - c[ordering[Symbol("x1")]] = Vector_(2, -0.1, -0.1); - c[ordering[Symbol("x2")]] = Vector_(2, 0.1, -0.2); + c[ordering[kl(1)]] = Vector_(2, -0.1, 0.1); + c[ordering[kx(1)]] = Vector_(2, -0.1, -0.1); + c[ordering[kx(2)]] = Vector_(2, 0.1, -0.2); return c; } /* ************************************************************************* */ VectorValues createZeroDelta(const Ordering& ordering) { VectorValues c(vector(3,2)); - c[ordering[Symbol(Symbol("l1"))]] = zero(2); - c[ordering[Symbol("x1")]] = zero(2); - c[ordering[Symbol("x2")]] = zero(2); + c[ordering[kl(1)]] = zero(2); + c[ordering[kx(1)]] = zero(2); + c[ordering[kx(2)]] = zero(2); return c; } @@ -144,16 +144,16 @@ namespace example { SharedDiagonal unit2 = noiseModel::Unit::Create(2); // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] - fg.add(ordering[Symbol("x1")], 10*eye(2), -1.0*ones(2), unit2); + fg.add(ordering[kx(1)], 10*eye(2), -1.0*ones(2), unit2); // odometry between x1 and x2: x2-x1=[0.2;-0.1] - fg.add(ordering[Symbol("x1")], -10*eye(2),ordering[Symbol("x2")], 10*eye(2), Vector_(2, 2.0, -1.0), unit2); + fg.add(ordering[kx(1)], -10*eye(2),ordering[kx(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2); // measurement between x1 and l1: l1-x1=[0.0;0.2] - fg.add(ordering[Symbol("x1")], -5*eye(2), ordering[Symbol("l1")], 5*eye(2), Vector_(2, 0.0, 1.0), unit2); + fg.add(ordering[kx(1)], -5*eye(2), ordering[kl(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2); // measurement between x2 and l1: l1-x2=[-0.2;0.3] - fg.add(ordering[Symbol("x2")], -5*eye(2), ordering[Symbol("l1")], 5*eye(2), Vector_(2, -1.0, 1.5), unit2); + fg.add(ordering[kx(2)], -5*eye(2), ordering[kl(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2); return *fg.dynamicCastFactors >(); } diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 7833bce18..7a8dc4825 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -12,9 +12,6 @@ #include using namespace boost; -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include @@ -74,7 +71,7 @@ TEST( GeneralSFMFactor, equals ) { // Create two identical factors and make sure they're equal Vector z = Vector_(2,323.,240.); - const Symbol cameraFrameNumber="x1", landmarkNumber="l1"; + const Symbol cameraFrameNumber('x',1), landmarkNumber('l',1); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); boost::shared_ptr factor1(new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); @@ -89,14 +86,14 @@ TEST( GeneralSFMFactor, equals ) TEST( GeneralSFMFactor, error ) { Point2 z(3.,0.); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); - boost::shared_ptr factor(new Projection(z, sigma, Symbol("x1"), Symbol("l1"))); + boost::shared_ptr factor(new Projection(z, sigma, Symbol('x',1), Symbol('l',1))); // For the following configuration, the factor predicts 320,240 Values values; Rot3 R; Point3 t1(0,0,-6); Pose3 x1(R,t1); - values.insert(Symbol("x1"), GeneralCamera(x1)); - Point3 l1; values.insert(Symbol("l1"), l1); + values.insert(Symbol('x',1), GeneralCamera(x1)); + Point3 l1; values.insert(Symbol('l',1), l1); EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values))); } diff --git a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp index 3f6d698d5..f762505a3 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp @@ -12,9 +12,6 @@ #include using namespace boost; -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include @@ -75,7 +72,7 @@ TEST( GeneralSFMFactor, equals ) { // Create two identical factors and make sure they're equal Vector z = Vector_(2,323.,240.); - const Symbol cameraFrameNumber="x1", landmarkNumber="l1"; + const Symbol cameraFrameNumber('x',1), landmarkNumber('l',1); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); boost::shared_ptr factor1(new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); @@ -91,14 +88,14 @@ TEST( GeneralSFMFactor, error ) { Point2 z(3.,0.); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); boost::shared_ptr - factor(new Projection(z, sigma, Symbol("x1"), Symbol("l1"))); + factor(new Projection(z, sigma, Symbol('x',1), Symbol('l',1))); // For the following configuration, the factor predicts 320,240 Values values; Rot3 R; Point3 t1(0,0,-6); Pose3 x1(R,t1); - values.insert(Symbol("x1"), GeneralCamera(x1)); - Point3 l1; values.insert(Symbol("l1"), l1); + values.insert(Symbol('x',1), GeneralCamera(x1)); + Point3 l1; values.insert(Symbol('l',1), l1); EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values))); } diff --git a/gtsam/slam/tests/testPose2SLAM.cpp b/gtsam/slam/tests/testPose2SLAM.cpp index 3bccccca3..81ce20334 100644 --- a/gtsam/slam/tests/testPose2SLAM.cpp +++ b/gtsam/slam/tests/testPose2SLAM.cpp @@ -14,9 +14,6 @@ * @author Frank Dellaert, Viorela Ila **/ -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include @@ -46,7 +43,7 @@ static noiseModel::Gaussian::shared_ptr covariance( ))); //static noiseModel::Gaussian::shared_ptr I3(noiseModel::Unit::Create(3)); -const Key kx0 = Symbol("x0"), kx1 = Symbol("x1"), kx2 = Symbol("x2"), kx3 = Symbol("x3"), kx4 = Symbol("x4"), kx5 = Symbol("x5"), kl1 = Symbol("l1"); +const Key kx0 = Symbol('x',0), kx1 = Symbol('x',1), kx2 = Symbol('x',2), kx3 = Symbol('x',3), kx4 = Symbol('x',4), kx5 = Symbol('x',5), kl1 = Symbol('l',1); /* ************************************************************************* */ // Test constraint, small displacement diff --git a/gtsam/slam/tests/testPose3SLAM.cpp b/gtsam/slam/tests/testPose3SLAM.cpp index c04bc2191..2edf6c4f0 100644 --- a/gtsam/slam/tests/testPose3SLAM.cpp +++ b/gtsam/slam/tests/testPose3SLAM.cpp @@ -28,9 +28,6 @@ using namespace boost::assign; // TODO: DANGEROUS, create shared pointers #define GTSAM_MAGIC_GAUSSIAN 6 -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include @@ -43,7 +40,7 @@ static Matrix covariance = eye(6); const double tol=1e-5; -const Key kx0 = Symbol("x0"), kx1 = Symbol("x1"), kx2 = Symbol("x2"), kx3 = Symbol("x3"), kx4 = Symbol("x4"), kx5 = Symbol("x5"); +const Key kx0 = Symbol('x',0), kx1 = Symbol('x',1), kx2 = Symbol('x',2), kx3 = Symbol('x',3), kx4 = Symbol('x',4), kx5 = Symbol('x',5); /* ************************************************************************* */ // test optimization with 6 poses arranged in a hexagon and a loop closure diff --git a/gtsam/slam/tests/testProjectionFactor.cpp b/gtsam/slam/tests/testProjectionFactor.cpp index ab8621cac..8b4ecbf21 100644 --- a/gtsam/slam/tests/testProjectionFactor.cpp +++ b/gtsam/slam/tests/testProjectionFactor.cpp @@ -18,9 +18,6 @@ #include -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include using namespace std; @@ -40,7 +37,7 @@ static Cal3_S2 K(fov,w,h); static SharedNoiseModel sigma(noiseModel::Unit::Create(1)); static shared_ptrK sK(new Cal3_S2(K)); -const Key kx1 = Symbol("x1"), kl1 = Symbol("l1"); +const Key kx1 = Symbol('x',1), kl1 = Symbol('l',1); // make cameras diff --git a/gtsam/slam/tests/testSerializationSLAM.cpp b/gtsam/slam/tests/testSerializationSLAM.cpp index afd759110..9cfb8bb72 100644 --- a/gtsam/slam/tests/testSerializationSLAM.cpp +++ b/gtsam/slam/tests/testSerializationSLAM.cpp @@ -16,8 +16,6 @@ * @date Feb 7, 2012 */ -#define GTSAM_MAGIC_KEY - #include #include #include @@ -51,7 +49,7 @@ BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); TEST (Serialization, smallExample_linear) { using namespace example; - Ordering ordering; ordering += Symbol("x1"),Symbol("x2"),Symbol("l1"); + Ordering ordering; ordering += Symbol('x',1),Symbol('x',2),Symbol('l',1); GaussianFactorGraph fg = createGaussianFactorGraph(ordering); EXPECT(equalsObj(ordering)); EXPECT(equalsXML(ordering)); diff --git a/gtsam/slam/tests/testVSLAM.cpp b/gtsam/slam/tests/testVSLAM.cpp index c4779a1cf..0188daa96 100644 --- a/gtsam/slam/tests/testVSLAM.cpp +++ b/gtsam/slam/tests/testVSLAM.cpp @@ -22,9 +22,6 @@ #include using namespace boost; -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testBoundingConstraint.cpp b/tests/testBoundingConstraint.cpp index 4fddf1ba0..09baec6e1 100644 --- a/tests/testBoundingConstraint.cpp +++ b/tests/testBoundingConstraint.cpp @@ -17,8 +17,6 @@ #include -#define GTSAM_MAGIC_KEY - #include #include #include @@ -153,7 +151,7 @@ TEST( testBoundingConstraint, unary_simple_optimization1) { Point2 start_pt(0.0, 1.0); shared_graph graph(new Graph()); - Symbol x1("x1"); + Symbol x1('x',1); graph->add(iq2D::PoseXInequality(x1, 1.0, true)); graph->add(iq2D::PoseYInequality(x1, 2.0, true)); graph->add(simulated2D::Prior(start_pt, soft_model2, x1)); @@ -175,7 +173,7 @@ TEST( testBoundingConstraint, unary_simple_optimization2) { Point2 start_pt(2.0, 3.0); shared_graph graph(new Graph()); - Symbol x1("x1"); + Symbol x1('x',1); graph->add(iq2D::PoseXInequality(x1, 1.0, false)); graph->add(iq2D::PoseYInequality(x1, 2.0, false)); graph->add(simulated2D::Prior(start_pt, soft_model2, x1)); @@ -191,7 +189,7 @@ TEST( testBoundingConstraint, unary_simple_optimization2) { /* ************************************************************************* */ TEST( testBoundingConstraint, MaxDistance_basics) { - Symbol key1("x1"), key2("x2"); + Symbol key1('x',1), key2('x',2); Point2 pt1, pt2(1.0, 0.0), pt3(2.0, 0.0), pt4(3.0, 0.0); iq2D::PoseMaxDistConstraint rangeBound(key1, key2, 2.0, mu); EXPECT_DOUBLES_EQUAL(2.0, rangeBound.threshold(), tol); @@ -233,7 +231,7 @@ TEST( testBoundingConstraint, MaxDistance_basics) { TEST( testBoundingConstraint, MaxDistance_simple_optimization) { Point2 pt1, pt2_init(5.0, 0.0), pt2_goal(2.0, 0.0); - Symbol x1("x1"), x2("x2"); + Symbol x1('x',1), x2('x',2); Graph graph; graph.add(simulated2D::equality_constraints::UnaryEqualityConstraint(pt1, x1)); @@ -256,7 +254,7 @@ TEST( testBoundingConstraint, MaxDistance_simple_optimization) { /* ************************************************************************* */ TEST( testBoundingConstraint, avoid_demo) { - Symbol x1("x1"), x2("x2"), x3("x3"), l1("l1"); + Symbol x1('x',1), x2('x',2), x3('x',3), l1('l',1); double radius = 1.0; Point2 x1_pt, x2_init(2.0, 0.5), x2_goal(2.0, 1.0), x3_pt(4.0, 0.0), l1_pt(2.0, 0.0); Point2 odo(2.0, 0.0); diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index 54761ddc9..927499050 100644 --- a/tests/testExtendedKalmanFilter.cpp +++ b/tests/testExtendedKalmanFilter.cpp @@ -16,8 +16,6 @@ #include -#define GTSAM_MAGIC_KEY - #include #include #include @@ -37,7 +35,7 @@ TEST( ExtendedKalmanFilter, linear ) { ExtendedKalmanFilter ekf(x_initial, P_initial); // Create the TestKeys for our example - Symbol x0("x0"), x1("x1"), x2("x2"), x3("x3"); + Symbol x0('x',0), x1('x',1), x2('x',2), x3('x',3); // Create the controls and measurement properties for our example double dt = 1.0; diff --git a/tests/testGaussianBayesNet.cpp b/tests/testGaussianBayesNet.cpp index dd8f49988..f0cec7530 100644 --- a/tests/testGaussianBayesNet.cpp +++ b/tests/testGaussianBayesNet.cpp @@ -25,9 +25,6 @@ #include // for operator += using namespace boost::assign; -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testGaussianFactor.cpp b/tests/testGaussianFactor.cpp index f39af5c3d..2cfb7a076 100644 --- a/tests/testGaussianFactor.cpp +++ b/tests/testGaussianFactor.cpp @@ -26,9 +26,6 @@ using namespace boost::assign; #include -// Magically casts strings like kx3 to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include @@ -44,7 +41,7 @@ static SharedDiagonal sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2), constraintModel = noiseModel::Constrained::All(2); -const Key kx1 = Symbol("x1"), kx2 = Symbol("x2"), kl1 = Symbol("l1"); +const Key kx1 = Symbol('x',1), kx2 = Symbol('x',2), kl1 = Symbol('l',1); /* ************************************************************************* */ TEST( GaussianFactor, linearFactor ) diff --git a/tests/testGaussianFactorGraph.cpp b/tests/testGaussianFactorGraph.cpp index bec246854..671d09cc7 100644 --- a/tests/testGaussianFactorGraph.cpp +++ b/tests/testGaussianFactorGraph.cpp @@ -28,9 +28,6 @@ using namespace boost::assign; #include -// Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testGaussianISAM.cpp b/tests/testGaussianISAM.cpp index 40ad8b428..b02d68583 100644 --- a/tests/testGaussianISAM.cpp +++ b/tests/testGaussianISAM.cpp @@ -21,9 +21,6 @@ using namespace boost::assign; #include -// Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index 443bc41fe..f41cff097 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -11,8 +11,6 @@ using namespace boost::assign; #include -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testGaussianJunctionTree.cpp b/tests/testGaussianJunctionTree.cpp index a00afae11..b01aa2ba4 100644 --- a/tests/testGaussianJunctionTree.cpp +++ b/tests/testGaussianJunctionTree.cpp @@ -25,9 +25,6 @@ #include using namespace boost::assign; -// Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testGraph.cpp b/tests/testGraph.cpp index 9131d801d..f56efae82 100644 --- a/tests/testGraph.cpp +++ b/tests/testGraph.cpp @@ -23,8 +23,6 @@ using namespace boost::assign; #include -#define GTSAM_MAGIC_KEY - // TODO: DANGEROUS, create shared pointers #define GTSAM_MAGIC_GAUSSIAN 3 diff --git a/tests/testInference.cpp b/tests/testInference.cpp index d1ef745e6..df8843415 100644 --- a/tests/testInference.cpp +++ b/tests/testInference.cpp @@ -17,9 +17,6 @@ #include -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index a12857ed5..d32a50fe5 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -25,9 +25,6 @@ // TODO: DANGEROUS, create shared pointers #define GTSAM_MAGIC_GAUSSIAN 2 -// Magically casts strings like PoseKey(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testNonlinearFactorGraph.cpp b/tests/testNonlinearFactorGraph.cpp index 08d50afb6..92e569038 100644 --- a/tests/testNonlinearFactorGraph.cpp +++ b/tests/testNonlinearFactorGraph.cpp @@ -27,9 +27,6 @@ using namespace boost::assign; #include -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 41db76e1e..e397ea443 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -26,9 +26,6 @@ using namespace boost::assign; #include using namespace boost; -// Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testSymbolicBayesNet.cpp b/tests/testSymbolicBayesNet.cpp index adddfab34..200530e6d 100644 --- a/tests/testSymbolicBayesNet.cpp +++ b/tests/testSymbolicBayesNet.cpp @@ -21,9 +21,6 @@ using namespace boost::assign; #include -// Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testSymbolicFactorGraph.cpp b/tests/testSymbolicFactorGraph.cpp index 596a715cb..f8fa777d1 100644 --- a/tests/testSymbolicFactorGraph.cpp +++ b/tests/testSymbolicFactorGraph.cpp @@ -20,9 +20,6 @@ using namespace boost::assign; #include -// Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/testTupleValues.cpp b/tests/testTupleValues.cpp index 06232c64e..d98afd5f6 100644 --- a/tests/testTupleValues.cpp +++ b/tests/testTupleValues.cpp @@ -20,9 +20,6 @@ #include -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include diff --git a/tests/timeGaussianFactorGraph.cpp b/tests/timeGaussianFactorGraph.cpp index 3af046971..3c9d83b3d 100644 --- a/tests/timeGaussianFactorGraph.cpp +++ b/tests/timeGaussianFactorGraph.cpp @@ -15,9 +15,6 @@ * @author Frank Dellaert */ -// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h -#define GTSAM_MAGIC_KEY - #include #include #include // for operator += in Ordering diff --git a/wrap/matlab.h b/wrap/matlab.h index 2c256a55d..631abb659 100644 --- a/wrap/matlab.h +++ b/wrap/matlab.h @@ -40,8 +40,6 @@ using namespace std; using namespace boost; // not usual, but for conciseness of generated code // start GTSAM Specifics ///////////////////////////////////////////////// -// to make keys be constructed from strings: -#define GTSAM_MAGIC_KEY // to enable Matrix and Vector constructor for SharedGaussian: #define GTSAM_MAGIC_GAUSSIAN // end GTSAM Specifics /////////////////////////////////////////////////