diff --git a/.gitignore b/.gitignore index 2682a6748..42bd27466 100644 --- a/.gitignore +++ b/.gitignore @@ -17,3 +17,5 @@ cython/gtsam.so cython/gtsam_wrapper.pxd .vscode .env +/.vs/ +/CMakeSettings.json diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index 63c512edb..b63e5faeb 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -251,10 +251,10 @@ void runIncremental() Key firstPose; while(nextMeasurement < datasetMeasurements.size()) { - if(BetweenFactor::shared_ptr measurement = + if(BetweenFactor::shared_ptr factor = boost::dynamic_pointer_cast >(datasetMeasurements[nextMeasurement])) { - Key key1 = measurement->key1(), key2 = measurement->key2(); + Key key1 = factor->key1(), key2 = factor->key2(); if(((int)key1 >= firstStep && key1 < key2) || ((int)key2 >= firstStep && key2 < key1)) { // We found an odometry starting at firstStep firstPose = std::min(key1, key2); @@ -302,52 +302,53 @@ void runIncremental() NonlinearFactor::shared_ptr measurementf = datasetMeasurements[nextMeasurement]; - if(BetweenFactor::shared_ptr measurement = + if(BetweenFactor::shared_ptr factor = boost::dynamic_pointer_cast >(measurementf)) { // Stop collecting measurements that are for future steps - if(measurement->key1() > step || measurement->key2() > step) + if(factor->key1() > step || factor->key2() > step) break; // Require that one of the nodes is the current one - if(measurement->key1() != step && measurement->key2() != step) + if(factor->key1() != step && factor->key2() != step) throw runtime_error("Problem in data file, out-of-sequence measurements"); // Add a new factor - newFactors.push_back(measurement); + newFactors.push_back(factor); + const auto& measured = factor->measured(); // Initialize the new variable - if(measurement->key1() > measurement->key2()) { - if(!newVariables.exists(measurement->key1())) { // Only need to check newVariables since loop closures come after odometry + if(factor->key1() > factor->key2()) { + if(!newVariables.exists(factor->key1())) { // Only need to check newVariables since loop closures come after odometry if(step == 1) - newVariables.insert(measurement->key1(), measurement->measured().inverse()); + newVariables.insert(factor->key1(), measured.inverse()); else { - Pose prevPose = isam2.calculateEstimate(measurement->key2()); - newVariables.insert(measurement->key1(), prevPose * measurement->measured().inverse()); + Pose prevPose = isam2.calculateEstimate(factor->key2()); + newVariables.insert(factor->key1(), prevPose * measured.inverse()); } } } else { - if(!newVariables.exists(measurement->key2())) { // Only need to check newVariables since loop closures come after odometry + if(!newVariables.exists(factor->key2())) { // Only need to check newVariables since loop closures come after odometry if(step == 1) - newVariables.insert(measurement->key2(), measurement->measured()); + newVariables.insert(factor->key2(), measured); else { - Pose prevPose = isam2.calculateEstimate(measurement->key1()); - newVariables.insert(measurement->key2(), prevPose * measurement->measured()); + Pose prevPose = isam2.calculateEstimate(factor->key1()); + newVariables.insert(factor->key2(), prevPose * measured); } } } } - else if(BearingRangeFactor::shared_ptr measurement = + else if(BearingRangeFactor::shared_ptr factor = boost::dynamic_pointer_cast >(measurementf)) { - Key poseKey = measurement->keys()[0], lmKey = measurement->keys()[1]; + Key poseKey = factor->keys()[0], lmKey = factor->keys()[1]; // Stop collecting measurements that are for future steps if(poseKey > step) throw runtime_error("Problem in data file, out-of-sequence measurements"); // Add new factor - newFactors.push_back(measurement); + newFactors.push_back(factor); // Initialize new landmark if(!isam2.getLinearizationPoint().exists(lmKey)) @@ -357,8 +358,9 @@ void runIncremental() pose = isam2.calculateEstimate(poseKey); else pose = newVariables.at(poseKey); - Rot2 measuredBearing = measurement->measured().first; - double measuredRange = measurement->measured().second; + const auto& measured = factor->measured(); + Rot2 measuredBearing = measured.bearing(); + double measuredRange = measured.range(); newVariables.insert(lmKey, pose.transform_from(measuredBearing.rotate(Point2(measuredRange, 0.0)))); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h index 41e18ff07..b91a50340 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h @@ -52,7 +52,7 @@ struct general_matrix_matrix_triangular_product& blocking) \ { \ - if ( lhs==rhs && ((UpLo&(Lower|Upper)==UpLo)) ) { \ + if ( lhs==rhs && ((UpLo&(Lower|Upper))==UpLo) ) { \ general_matrix_matrix_rankupdate \ ::run(size,depth,lhs,lhsStride,rhs,rhsStride,res,resStride,alpha,blocking); \ } else { \ diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 93a7d0db5..87ddf574c 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -110,7 +110,7 @@ public: * Clone this value (normal clone on the heap, delete with 'delete' operator) */ virtual boost::shared_ptr clone() const { - return boost::make_shared(*this); + return boost::allocate_shared(Eigen::aligned_allocator(), *this); } /// Generic Value interface version of retract diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index b30edb3df..7bfdd7ea5 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -168,9 +168,9 @@ struct FixedDimension { "FixedDimension instantiated for dymanically-sized type."); }; +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// Helper class to construct the product manifold of two other manifolds, M1 and M2 -/// Assumes nothing except manifold structure for M1 and M2, and the existence -/// of default constructor for those types +/// Deprecated because of limited usefulness, maximum obfuscation template class ProductManifold: public std::pair { BOOST_CONCEPT_ASSERT((IsManifold)); @@ -209,12 +209,19 @@ public: v << v1, v2; return v; } + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0 + }; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Define any direct product group to be a model of the multiplicative Group concept template struct traits > : internal::Manifold > { }; +#endif } // \ namespace gtsam diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index b1e003864..ffa373027 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -45,23 +45,39 @@ struct Range; * and BearingRange(pose,point) will return pair */ template -struct BearingRange - : public ProductManifold::result_type, - typename Range::result_type> { +struct BearingRange { +private: typedef typename Bearing::result_type B; typedef typename Range::result_type R; - typedef ProductManifold Base; + B bearing_; + R range_; + +public: + enum { dimB = traits::dimension }; + enum { dimR = traits::dimension }; + enum { dimension = dimB + dimR }; + + /// @name Standard Constructors + /// @{ BearingRange() {} - BearingRange(const ProductManifold& br) : Base(br) {} - BearingRange(const B& b, const R& r) : Base(b, r) {} + BearingRange(const B& b, const R& r) : bearing_(b), range_(r) {} + + /// @} + /// @name Standard Interface + /// @{ + + /// Return bearing measurement + const B& bearing() const { return bearing_; } + + /// Return range measurement + const R& range() const { return range_; } /// Prediction function that stacks measurements static BearingRange Measure( - const A1& a1, const A2& a2, - OptionalJacobian::dimension> H1 = boost::none, - OptionalJacobian::dimension> H2 = - boost::none) { + const A1& a1, const A2& a2, + OptionalJacobian::dimension> H1 = boost::none, + OptionalJacobian::dimension> H2 = boost::none) { typename MakeJacobian::type HB1; typename MakeJacobian::type HB2; typename MakeJacobian::type HR1; @@ -75,32 +91,75 @@ struct BearingRange return BearingRange(b, r); } + /// @} + /// @name Testable + /// @{ + void print(const std::string& str = "") const { std::cout << str; - traits::Print(this->first, "bearing "); - traits::Print(this->second, "range "); + traits::Print(bearing_, "bearing "); + traits::Print(range_, "range "); } bool equals(const BearingRange& m2, double tol = 1e-8) const { - return traits::Equals(this->first, m2.first, tol) && - traits::Equals(this->second, m2.second, tol); + return traits::Equals(bearing_, m2.bearing_, tol) && + traits::Equals(range_, m2.range_, tol); } - private: + /// @} + /// @name Manifold + /// @{ + + inline static size_t Dim() { return dimension; } + inline size_t dim() const { return dimension; } + + typedef Eigen::Matrix TangentVector; + typedef OptionalJacobian ChartJacobian; + + /// Retract delta to manifold + BearingRange retract(const TangentVector& xi) const { + B m1 = traits::Retract(bearing_, xi.template head()); + R m2 = traits::Retract(range_, xi.template tail()); + return BearingRange(m1, m2); + } + + /// Compute the coordinates in the tangent space + TangentVector localCoordinates(const BearingRange& other) const { + typename traits::TangentVector v1 = traits::Local(bearing_, other.bearing_); + typename traits::TangentVector v2 = traits::Local(range_, other.range_); + TangentVector v; + v << v1, v2; + return v; + } + + /// @} + /// @name Advanced Interface + /// @{ + +private: /// Serialization function template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp("bearing", this->first); - ar& boost::serialization::make_nvp("range", this->second); + ar& boost::serialization::make_nvp("bearing", bearing_); + ar& boost::serialization::make_nvp("range", range_); } friend class boost::serialization::access; + + /// @} + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { + NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0 + }; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Declare this to be both Testable and a Manifold template struct traits > - : Testable >, - internal::ManifoldTraits > {}; + : Testable >, + internal::ManifoldTraits > {}; // Helper class for to implement Range traits for classes with a bearing method // For example, to specialize Bearing to Pose3 and Point3, using Pose3::bearing, it suffices to say diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index db9caf13b..acb3cacaf 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -229,10 +229,6 @@ private: void serialize(Archive & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_NVP(pose_); } - -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - }; // end of class PinholeBase @@ -416,9 +412,6 @@ private: } /// @} - -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index 9dec574eb..308250033 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -11,7 +11,9 @@ #include #include #include + #include +#include namespace gtsam { @@ -21,19 +23,13 @@ namespace gtsam { * but here we choose instead to parameterize it as a (Rot3,Unit3) pair. * We can then non-linearly optimize immediately on this 5-dimensional manifold. */ -class GTSAM_EXPORT EssentialMatrix : private ProductManifold { - -private: - typedef ProductManifold Base; - Matrix3 E_; ///< Essential matrix - - /// Construct from Base - EssentialMatrix(const Base& base) : - Base(base), E_(direction().skew() * rotation().matrix()) { - } - -public: +class GTSAM_EXPORT EssentialMatrix { + private: + Rot3 R_; ///< Rotation + Unit3 t_; ///< Translation + Matrix3 E_; ///< Essential matrix + public: /// Static function to convert Point2 to homogeneous coordinates static Vector3 Homogeneous(const Point2& p) { return Vector3(p.x(), p.y(), 1); @@ -43,13 +39,12 @@ public: /// @{ /// Default constructor - EssentialMatrix() : - Base(Rot3(), Unit3(1, 0, 0)), E_(direction().skew()) { + EssentialMatrix() :E_(t_.skew()) { } /// Construct from rotation and translation EssentialMatrix(const Rot3& aRb, const Unit3& aTb) : - Base(aRb, aTb), E_(direction().skew() * rotation().matrix()) { + R_(aRb), t_(aTb), E_(t_.skew() * R_.matrix()) { } /// Named constructor with derivatives @@ -79,27 +74,32 @@ public: /// assert equality up to a tolerance bool equals(const EssentialMatrix& other, double tol = 1e-8) const { - return rotation().equals(other.rotation(), tol) - && direction().equals(other.direction(), tol); + return R_.equals(other.R_, tol) + && t_.equals(other.t_, tol); } /// @} /// @name Manifold /// @{ + enum { dimension = 5 }; + inline static size_t Dim() { return dimension;} + inline size_t dim() const { return dimension;} - using Base::dimension; - using Base::dim; - using Base::Dim; + typedef OptionalJacobian ChartJacobian; /// Retract delta to manifold - EssentialMatrix retract(const TangentVector& v) const { - return Base::retract(v); + EssentialMatrix retract(const Vector5& xi) const { + return EssentialMatrix(R_.retract(xi.head<3>()), t_.retract(xi.tail<2>())); } /// Compute the coordinates in the tangent space - TangentVector localCoordinates(const EssentialMatrix& other) const { - return Base::localCoordinates(other); + Vector5 localCoordinates(const EssentialMatrix& other) const { + auto v1 = R_.localCoordinates(other.R_); + auto v2 = t_.localCoordinates(other.t_); + Vector5 v; + v << v1, v2; + return v; } /// @} @@ -108,12 +108,12 @@ public: /// Rotation inline const Rot3& rotation() const { - return this->first; + return R_; } /// Direction inline const Unit3& direction() const { - return this->second; + return t_; } /// Return 3*3 matrix representation @@ -123,12 +123,12 @@ public: /// Return epipole in image_a , as Unit3 to allow for infinity inline const Unit3& epipole_a() const { - return direction(); + return t_; } /// Return epipole in image_b, as Unit3 to allow for infinity inline Unit3 epipole_b() const { - return rotation().unrotate(direction()); + return R_.unrotate(t_); } /** @@ -139,8 +139,8 @@ public: * @return point in pose coordinates */ Point3 transform_to(const Point3& p, - OptionalJacobian<3,5> DE = boost::none, - OptionalJacobian<3,3> Dpoint = boost::none) const; + OptionalJacobian<3, 5> DE = boost::none, + OptionalJacobian<3, 3> Dpoint = boost::none) const; /** * Given essential matrix E in camera frame B, convert to body frame C @@ -160,8 +160,8 @@ public: } /// epipolar error, algebraic - double error(const Vector3& vA, const Vector3& vB, // - OptionalJacobian<1,5> H = boost::none) const; + double error(const Vector3& vA, const Vector3& vB, + OptionalJacobian<1, 5> H = boost::none) const; /// @} @@ -176,8 +176,7 @@ public: /// @} -private: - + private: /// @name Advanced Interface /// @{ @@ -185,21 +184,24 @@ private: friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_NVP(first); - ar & BOOST_SERIALIZATION_NVP(second); + ar & BOOST_SERIALIZATION_NVP(R_); + ar & BOOST_SERIALIZATION_NVP(t_); - ar & boost::serialization::make_nvp("E11", E_(0,0)); - ar & boost::serialization::make_nvp("E12", E_(0,1)); - ar & boost::serialization::make_nvp("E13", E_(0,2)); - ar & boost::serialization::make_nvp("E21", E_(1,0)); - ar & boost::serialization::make_nvp("E22", E_(1,1)); - ar & boost::serialization::make_nvp("E23", E_(1,2)); - ar & boost::serialization::make_nvp("E31", E_(2,0)); - ar & boost::serialization::make_nvp("E32", E_(2,1)); - ar & boost::serialization::make_nvp("E33", E_(2,2)); + ar & boost::serialization::make_nvp("E11", E_(0, 0)); + ar & boost::serialization::make_nvp("E12", E_(0, 1)); + ar & boost::serialization::make_nvp("E13", E_(0, 2)); + ar & boost::serialization::make_nvp("E21", E_(1, 0)); + ar & boost::serialization::make_nvp("E22", E_(1, 1)); + ar & boost::serialization::make_nvp("E23", E_(1, 2)); + ar & boost::serialization::make_nvp("E31", E_(2, 0)); + ar & boost::serialization::make_nvp("E32", E_(2, 1)); + ar & boost::serialization::make_nvp("E33", E_(2, 2)); } /// @} + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; template<> @@ -208,5 +210,5 @@ struct traits : public internal::Manifold {}; template<> struct traits : public internal::Manifold {}; -} // gtsam +} // namespace gtsam diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 1ba384857..f03e0852e 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -278,6 +278,12 @@ private: ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(r_); } + +#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS +public: + // Make sure Pose2 is aligned if it contains a Vector2 + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; // Pose2 /** specialization for pose2 wedge function (generic template in Lie.h) */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 3229cbbbe..ca0fdff10 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -327,9 +327,11 @@ public: } /// @} - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - +#ifdef GTSAM_USE_QUATERNIONS + // Align if we are using Quaternions + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; // Pose3 class diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 65dd5f609..eaec62b48 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -59,7 +59,7 @@ namespace gtsam { /// Named constructor from angle in degrees static Rot2 fromDegrees(double theta) { - const double degree = M_PI / 180; + static const double degree = M_PI / 180; return fromAngle(theta * degree); } diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 263301122..985c521a2 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -508,9 +508,11 @@ namespace gtsam { #endif } - public: +#ifdef GTSAM_USE_QUATERNIONS + // only align if quaternion, Matrix3 has no alignment requirements + public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - +#endif }; /** diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 016488701..6be3b89c2 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -26,6 +26,8 @@ #include #include +#include // for Eigen::aligned_allocator + #include #include #include @@ -161,11 +163,11 @@ namespace gtsam { factors_.push_back(factor); } /** Emplace a factor */ - template - typename std::enable_if::value>::type - emplace_shared(Args&&... args) { - factors_.push_back(boost::make_shared(std::forward(args)...)); - } + template + typename std::enable_if::value>::type + emplace_shared(Args&&... args) { + factors_.push_back(boost::allocate_shared(Eigen::aligned_allocator(), std::forward(args)...)); + } /** push back many factors with an iterator over shared_ptr (factors are not copied) */ template @@ -194,7 +196,7 @@ namespace gtsam { template typename std::enable_if::value>::type push_back(const DERIVEDFACTOR& factor) { - factors_.push_back(boost::make_shared(factor)); + factors_.push_back(boost::allocate_shared(Eigen::aligned_allocator(), factor)); } //#endif diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 21f74ac06..4ae6078e9 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -129,6 +129,9 @@ private: ar & BOOST_SERIALIZATION_NVP(nZ_); ar & BOOST_SERIALIZATION_NVP(bRef_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /// traits @@ -213,6 +216,9 @@ private: ar & BOOST_SERIALIZATION_NVP(nZ_); ar & BOOST_SERIALIZATION_NVP(bRef_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 21c4200a9..1967e4a56 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -252,8 +252,8 @@ CombinedImuFactor::CombinedImuFactor( : Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, pose_j, vel_j, bias_i, bias_j), _PIM_(pim) { - boost::shared_ptr p = - boost::make_shared(pim.p()); + using P = CombinedPreintegratedMeasurements::Params; + auto p = boost::allocate_shared

(Eigen::aligned_allocator

(), pim.p()); p->n_gravity = n_gravity; p->omegaCoriolis = omegaCoriolis; p->body_P_sensor = body_P_sensor; diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 6fd98bfcb..7ca7fe463 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -320,6 +320,9 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // class CombinedImuFactor diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 54320417d..bf2f5c0c8 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -59,8 +59,11 @@ struct GTSAM_EXPORT PreintegratedRotationParams { ar & BOOST_SERIALIZATION_NVP(body_P_sensor); } +#ifdef GTSAM_USE_QUATERNIONS + // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; /** @@ -169,8 +172,11 @@ class GTSAM_EXPORT PreintegratedRotation { ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); } - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#ifdef GTSAM_USE_QUATERNIONS + // Align if we are using Quaternions + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; template <> diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index cf5465c05..3c22a1d00 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -202,7 +202,8 @@ public: /// @} #endif - /// @} +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 7bff82365..3a2fb467a 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -75,8 +75,11 @@ protected: ar & BOOST_SERIALIZATION_NVP(n_gravity); } +#ifdef GTSAM_USE_QUATERNIONS + // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; } // namespace gtsam diff --git a/gtsam/navigation/tests/testGPSFactor.cpp b/gtsam/navigation/tests/testGPSFactor.cpp index 293bffa00..9457f501d 100644 --- a/gtsam/navigation/tests/testGPSFactor.cpp +++ b/gtsam/navigation/tests/testGPSFactor.cpp @@ -22,19 +22,26 @@ #include +#include #include using namespace std; using namespace gtsam; using namespace GeographicLib; +#if GEOGRAPHICLIB_VERSION_MINOR<37 +static const auto& kWGS84 = Geocentric::WGS84; +#else +static const auto& kWGS84 = Geocentric::WGS84(); +#endif + // ************************************************************************* namespace example { // ENU Origin is where the plane was in hold next to runway const double lat0 = 33.86998, lon0 = -84.30626, h0 = 274; // Convert from GPS to ENU -LocalCartesian origin_ENU(lat0, lon0, h0, Geocentric::WGS84); +LocalCartesian origin_ENU(lat0, lon0, h0, kWGS84); // Dekalb-Peachtree Airport runway 2L const double lat = 33.87071, lon = -84.30482, h = 274; @@ -107,8 +114,7 @@ TEST(GPSData, init) { // GPS Reading 1 will be ENU origin double t1 = 84831; Point3 NED1(0, 0, 0); - LocalCartesian enu(35.4393283333333, -119.062986666667, 275.54, - Geocentric::WGS84); + LocalCartesian enu(35.4393283333333, -119.062986666667, 275.54, kWGS84); // GPS Readin 2 double t2 = 84831.5; diff --git a/gtsam/navigation/tests/testGeographicLib.cpp b/gtsam/navigation/tests/testGeographicLib.cpp index aaa01b54d..6c495faf5 100644 --- a/gtsam/navigation/tests/testGeographicLib.cpp +++ b/gtsam/navigation/tests/testGeographicLib.cpp @@ -15,6 +15,7 @@ * @author Frank Dellaert */ +#include #include #include #include @@ -29,21 +30,27 @@ using namespace std; using namespace GeographicLib; // Dekalb-Peachtree Airport runway 2L -const double lat = 33.87071, lon = -84.30482, h = 274; +static const double lat = 33.87071, lon = -84.30482, h = 274; + +#if GEOGRAPHICLIB_VERSION_MINOR<37 +static const auto& kWGS84 = Geocentric::WGS84; +#else +static const auto& kWGS84 = Geocentric::WGS84(); +#endif //************************************************************************** TEST( GeographicLib, Geocentric) { // From lat-lon to geocentric double X, Y, Z; - Geocentric::WGS84.Forward(lat, lon, h, X, Y, Z); + kWGS84.Forward(lat, lon, h, X, Y, Z); EXPECT_DOUBLES_EQUAL(526, X/1000, 1); EXPECT_DOUBLES_EQUAL(-5275, Y/1000, 1); EXPECT_DOUBLES_EQUAL(3535, Z/1000, 1); // From geocentric to lat-lon double lat_, lon_, h_; - Geocentric::WGS84.Reverse(X, Y, Z, lat_, lon_, h_); + kWGS84.Reverse(X, Y, Z, lat_, lon_, h_); EXPECT_DOUBLES_EQUAL(lat, lat_, 1e-5); EXPECT_DOUBLES_EQUAL(lon, lon_, 1e-5); EXPECT_DOUBLES_EQUAL(h, h_, 1e-5); @@ -69,11 +76,9 @@ TEST( GeographicLib, UTM) { //************************************************************************** TEST( GeographicLib, ENU) { - const Geocentric& earth = Geocentric::WGS84; - // ENU Origin is where the plane was in hold next to runway const double lat0 = 33.86998, lon0 = -84.30626, h0 = 274; - LocalCartesian enu(lat0, lon0, h0, earth); + LocalCartesian enu(lat0, lon0, h0, kWGS84); // From lat-lon to geocentric double E, N, U; diff --git a/gtsam/nonlinear/Expression-inl.h b/gtsam/nonlinear/Expression-inl.h index 22172e44f..0ba2ad446 100644 --- a/gtsam/nonlinear/Expression-inl.h +++ b/gtsam/nonlinear/Expression-inl.h @@ -200,7 +200,7 @@ T Expression::valueAndJacobianMap(const Values& values, // allocated on Visual Studio. For more information see the issue below // https://bitbucket.org/gtborg/gtsam/issue/178/vlas-unsupported-in-visual-studio #ifdef _MSC_VER - internal::ExecutionTraceStorage* traceStorage = new internal::ExecutionTraceStorage[size]; + auto traceStorage = static_cast(_aligned_malloc(size, internal::TraceAlignment)); #else internal::ExecutionTraceStorage traceStorage[size]; #endif @@ -210,7 +210,7 @@ T Expression::valueAndJacobianMap(const Values& values, trace.startReverseAD1(jacobians); #ifdef _MSC_VER - delete[] traceStorage; + _aligned_free(traceStorage); #endif return value; diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 64a8a6bb6..34ba8e1ff 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -205,6 +205,11 @@ private: BOOST_SERIALIZATION_SPLIT_MEMBER() friend class boost::serialization::access; + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // ExpressionFactor diff --git a/gtsam/nonlinear/ExpressionFactorGraph.h b/gtsam/nonlinear/ExpressionFactorGraph.h index 122bd429f..665f887e2 100644 --- a/gtsam/nonlinear/ExpressionFactorGraph.h +++ b/gtsam/nonlinear/ExpressionFactorGraph.h @@ -42,7 +42,8 @@ public: template void addExpressionFactor(const Expression& h, const T& z, const SharedNoiseModel& R) { - push_back(boost::make_shared >(R, z, h)); + using F = ExpressionFactor; + push_back(boost::allocate_shared(Eigen::aligned_allocator(), R, z, h)); } /// @} diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index f3fd49fa7..89291fac5 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -122,6 +122,11 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // \class BetweenFactor /// traits diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 92a78279b..179200fe1 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -103,6 +103,9 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measuredE_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // \class EssentialMatrixConstraint diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index 9a3a4a47a..3c5c42ccc 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -104,6 +104,11 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(prior_); } + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; } /// namespace gtsam diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index d13c28e11..8332acabc 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -186,7 +186,10 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } - }; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; /// traits template