Switch to the new alignment marker type

release/4.3a0
Fan Jiang 2020-06-24 17:15:00 -04:00
parent 6dbd7c243a
commit fb21c553a0
31 changed files with 48 additions and 39 deletions

View File

@ -181,7 +181,7 @@ public:
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
};
/// use this macro instead of BOOST_CLASS_EXPORT for GenericValues

View File

@ -214,7 +214,7 @@ public:
enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0
};
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
};
// Define any direct product group to be a model of the multiplicative Group concept

View File

@ -268,3 +268,12 @@ namespace gtsam {
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \
EIGEN_MAKE_ALIGNED_OPERATOR_NEW \
using _eigen_aligned_allocator_trait = void;
/**
* This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned
* memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug.
* See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation.
*/
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \
using _eigen_aligned_allocator_trait = void;

View File

@ -162,7 +162,7 @@ private:
NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0
};
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
};
// Declare this to be both Testable and a Manifold

View File

@ -319,7 +319,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
template<class CAMERA>

View File

@ -212,7 +212,7 @@ class EssentialMatrix {
/// @}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
template<>

View File

@ -325,7 +325,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// manifold traits

View File

@ -222,7 +222,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// end of class PinholeBaseK
@ -425,7 +425,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// end of class PinholePose

View File

@ -317,7 +317,7 @@ public:
public:
// Align for Point2, which is either derived from, or is typedef, of Vector2
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
}; // Pose2
/** specialization for pose2 wedge function (generic template in Lie.h) */

View File

@ -355,7 +355,7 @@ public:
#ifdef GTSAM_USE_QUATERNIONS
// Align if we are using Quaternions
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#endif
};
// Pose3 class

View File

@ -544,7 +544,7 @@ namespace gtsam {
#ifdef GTSAM_USE_QUATERNIONS
// only align if quaternion, Matrix3 has no alignment requirements
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#endif
};

View File

@ -54,7 +54,7 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
using VectorN2 = Eigen::Matrix<double, internal::NSquaredSO(N), 1>;
using MatrixDD = Eigen::Matrix<double, dimension, dimension>;
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(true)
protected:
MatrixNN matrix_; ///< Rotation matrix

View File

@ -214,7 +214,7 @@ private:
/// @}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// Define GTSAM traits

View File

@ -215,7 +215,7 @@ struct CameraProjectionMatrix {
private:
const Matrix3 K_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
/**

View File

@ -139,7 +139,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
/// traits
@ -219,7 +219,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
/// traits

View File

@ -100,7 +100,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
@ -210,7 +210,7 @@ public:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
/**
@ -332,7 +332,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// class CombinedImuFactor

View File

@ -171,7 +171,7 @@ private:
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
/// @}
}; // ConstantBias class

View File

@ -69,7 +69,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams {
#ifdef GTSAM_USE_QUATERNIONS
// Align if we are using Quaternions
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#endif
};
@ -182,7 +182,7 @@ class GTSAM_EXPORT PreintegratedRotation {
#ifdef GTSAM_USE_QUATERNIONS
// Align if we are using Quaternions
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#endif
};

View File

@ -214,7 +214,7 @@ class GTSAM_EXPORT PreintegrationBase {
#endif
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
} /// namespace gtsam

View File

@ -84,7 +84,7 @@ protected:
#ifdef GTSAM_USE_QUATERNIONS
// Align if we are using Quaternions
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#endif
};

View File

@ -141,7 +141,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
} /// namespace gtsam

View File

@ -209,7 +209,7 @@ private:
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
};
// ExpressionFactor

View File

@ -175,7 +175,7 @@ public:
/// @}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
private:
@ -265,7 +265,7 @@ public:
traits<X>::Print(value_, "Value");
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
private:
@ -331,7 +331,7 @@ public:
return traits<X>::Local(x1,x2);
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
private:

View File

@ -114,7 +114,7 @@ namespace gtsam {
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
};
} /// namespace gtsam

View File

@ -150,7 +150,7 @@ public:
return constant_;
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
//-----------------------------------------------------------------------------

View File

@ -126,7 +126,7 @@ namespace gtsam {
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 };
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
}; // \class BetweenFactor
/// traits

View File

@ -105,7 +105,7 @@ private:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// \class EssentialMatrixConstraint

View File

@ -81,7 +81,7 @@ public:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
/**
@ -201,7 +201,7 @@ public:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// EssentialMatrixFactor2
@ -286,7 +286,7 @@ public:
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
// EssentialMatrixFactor3

View File

@ -189,7 +189,7 @@ namespace gtsam {
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
/// traits

View File

@ -113,7 +113,7 @@ public:
return error;
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace gtsam

View File

@ -81,7 +81,7 @@ protected:
mutable FBlocks Fs;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<This> shared_ptr;