diff --git a/.cproject b/.cproject index 7b099eb53..ff704cea8 100644 --- a/.cproject +++ b/.cproject @@ -510,22 +510,6 @@ true true - - make - -j5 - SFMExampleExpressions.run - true - true - true - - - make - -j5 - Pose2SLAMExampleExpressions.run - true - true - true - make -j5 @@ -3102,6 +3086,22 @@ true true + + make + -j4 + Pose2SLAMExampleExpressions.run + true + true + true + + + make + -j4 + SFMExampleExpressions.run + true + true + true + make -j5 diff --git a/gtsam_unstable/examples/Pose2SLAMExampleExpressions.cpp b/examples/Pose2SLAMExampleExpressions.cpp similarity index 100% rename from gtsam_unstable/examples/Pose2SLAMExampleExpressions.cpp rename to examples/Pose2SLAMExampleExpressions.cpp diff --git a/gtsam_unstable/examples/SFMExampleExpressions.cpp b/examples/SFMExampleExpressions.cpp similarity index 100% rename from gtsam_unstable/examples/SFMExampleExpressions.cpp rename to examples/SFMExampleExpressions.cpp diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index 018a15dd8..923b0b9de 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -72,22 +72,22 @@ typedef NoiseModelFactor1 NM1; typedef NoiseModelFactor2 NM2; typedef BearingRangeFactor BR; -GTSAM_VALUE_EXPORT(Value); -GTSAM_VALUE_EXPORT(Pose); -GTSAM_VALUE_EXPORT(Rot2); -GTSAM_VALUE_EXPORT(Point2); -GTSAM_VALUE_EXPORT(NonlinearFactor); -GTSAM_VALUE_EXPORT(NoiseModelFactor); -GTSAM_VALUE_EXPORT(NM1); -GTSAM_VALUE_EXPORT(NM2); -GTSAM_VALUE_EXPORT(BetweenFactor); -GTSAM_VALUE_EXPORT(PriorFactor); -GTSAM_VALUE_EXPORT(BR); -GTSAM_VALUE_EXPORT(noiseModel::Base); -GTSAM_VALUE_EXPORT(noiseModel::Isotropic); -GTSAM_VALUE_EXPORT(noiseModel::Gaussian); -GTSAM_VALUE_EXPORT(noiseModel::Diagonal); -GTSAM_VALUE_EXPORT(noiseModel::Unit); +//GTSAM_VALUE_EXPORT(Value); +//GTSAM_VALUE_EXPORT(Pose); +//GTSAM_VALUE_EXPORT(Rot2); +//GTSAM_VALUE_EXPORT(Point2); +//GTSAM_VALUE_EXPORT(NonlinearFactor); +//GTSAM_VALUE_EXPORT(NoiseModelFactor); +//GTSAM_VALUE_EXPORT(NM1); +//GTSAM_VALUE_EXPORT(NM2); +//GTSAM_VALUE_EXPORT(BetweenFactor); +//GTSAM_VALUE_EXPORT(PriorFactor); +//GTSAM_VALUE_EXPORT(BR); +//GTSAM_VALUE_EXPORT(noiseModel::Base); +//GTSAM_VALUE_EXPORT(noiseModel::Isotropic); +//GTSAM_VALUE_EXPORT(noiseModel::Gaussian); +//GTSAM_VALUE_EXPORT(noiseModel::Diagonal); +//GTSAM_VALUE_EXPORT(noiseModel::Unit); double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) { // Compute degrees of freedom (observations - variables) @@ -295,7 +295,7 @@ void runIncremental() NonlinearFactorGraph newFactors; Values newVariables; - newFactors.push_back(boost::make_shared >(firstPose, Pose(), noiseModel::Unit::Create(Pose::Dim()))); + newFactors.push_back(boost::make_shared >(firstPose, Pose(), noiseModel::Unit::Create(3))); newVariables.insert(firstPose, Pose()); isam2.update(newFactors, newVariables); @@ -474,7 +474,7 @@ void runBatch() cout << "Creating batch optimizer..." << endl; NonlinearFactorGraph measurements = datasetMeasurements; - measurements.push_back(boost::make_shared >(0, Pose(), noiseModel::Unit::Create(Pose::Dim()))); + measurements.push_back(boost::make_shared >(0, Pose(), noiseModel::Unit::Create(3))); gttic_(Create_optimizer); GaussNewtonParams params; diff --git a/gtsam/base/Lie.h b/gtsam/base/Lie.h index 4a42bccf8..9c410ac25 100644 --- a/gtsam/base/Lie.h +++ b/gtsam/base/Lie.h @@ -144,9 +144,6 @@ struct LieGroupTraits : Testable { /// @{ typedef multiplicative_group_tag group_flavor; static Class Identity() { return Class::identity();} - static Class Compose(const Class& m1, const Class& m2) { return m1 * m2;} - static Class Between(const Class& m1, const Class& m2) { return m1.inverse() * m2;} - static Class Inverse(const Class& m) { return m.inverse();} /// @} /// @name Manifold @@ -161,21 +158,13 @@ struct LieGroupTraits : Testable { static int GetDimension(const Class&) {return dimension;} - static TangentVector Local(const Class& origin, const Class& other) { - return origin.localCoordinates(other); - } - - static Class Retract(const Class& origin, const TangentVector& v) { - return origin.retract(v); - } - static TangentVector Local(const Class& origin, const Class& other, - ChartJacobian Horigin, ChartJacobian Hother = boost::none) { + ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) { return origin.localCoordinates(other, Horigin, Hother); } static Class Retract(const Class& origin, const TangentVector& v, - ChartJacobian Horigin, ChartJacobian Hv = boost::none) { + ChartJacobian Horigin = boost::none, ChartJacobian Hv = boost::none) { return origin.retract(v, Horigin, Hv); } @@ -192,17 +181,18 @@ struct LieGroupTraits : Testable { return Class::Expmap(v, Hv); } - static Class Compose(const Class& m1, const Class& m2, ChartJacobian H1, - ChartJacobian H2 = boost::none) { + static Class Compose(const Class& m1, const Class& m2, // + ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { return m1.compose(m2, H1, H2); } - static Class Between(const Class& m1, const Class& m2, ChartJacobian H1, - ChartJacobian H2 = boost::none) { + static Class Between(const Class& m1, const Class& m2, // + ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { return m1.between(m2, H1, H2); } - static Class Inverse(const Class& m, ChartJacobian H) { + static Class Inverse(const Class& m, // + ChartJacobian H = boost::none) { return m.inverse(H); } diff --git a/gtsam/nonlinear/expressions.h b/gtsam/nonlinear/expressions.h index 18d0d5d8f..a549517e5 100644 --- a/gtsam/nonlinear/expressions.h +++ b/gtsam/nonlinear/expressions.h @@ -8,14 +8,14 @@ #pragma once #include -#include +#include namespace gtsam { // Generics template Expression between(const Expression& t1, const Expression& t2) { - return Expression(t1, &T::between, t2); + return Expression(traits::Between, t1, t2); } typedef Expression double_;