Description
Description
I am having non-consistent behaviour with using a memory-sanitizer (-fsanitize=address
). I get different results for instance depending on when I run it locally on my machine versus running the same in a Docker... I suspect it has to do with the use of the EIGEN_MAKE_ALIGNED_OPERATOR_NEW
-flag.
Eigen has a special define that should be used in classes that have Eigen-types as member variables: EIGEN_MAKE_ALIGNED_OPERATOR_NEW
. Many GTSAM-classes have this; e.g. CombinedImuFactor.h
and ImuBias.h
, however, many do not have this flag even though they have Eigen-members: ImuFactor.h
for instance. Some do not have it but inherit it from their parent class, e.g. ManifoldPreintegration.h
does not have it, but its base-class PreintegrationBase.h
does. And TangenPreintegration.h
does have it (even though its base-class also has it).. Noteworthy is that none of the noisemodels use it.
Steps to reproduce
I do not have a minimal working example yet to share. If I build everything (gtsam & project) with Debug
it is fine. However, using Release
I get something like:
1: ==15494==ERROR: AddressSanitizer: attempting free on address which was not malloc()-ed: 0x607000000b20 in thread T0
1: #0 0x7f02eeb3d7b8 in __interceptor_free (/usr/lib/x86_64-linux-gnu/libasan.so.4+0xde7b8)
1: #1 0x7f02ee09a6ae in Eigen::internal::compute_inverse<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, -1>::run(Eigen::Matrix<double, -1, -1, 0, -1, -1> const&, Eigen::Matrix<double, -1, -1, 0, -1, -1>&) (/usr/local/lib/libgtsam.so.4+0x25d6ae)
1: #2 0x7f02ee09675e in gtsam::noiseModel::Gaussian::Covariance(Eigen::Matrix<double, -1, -1, 0, -1, -1> const&, bool) (/usr/local/lib/libgtsam.so.4+0x25975e)
1: #3 0x7f02ee14b581 in gtsam::CombinedImuFactor::CombinedImuFactor(unsigned long, unsigned long, unsigned long, unsigned long, unsigned long, unsigned long, gtsam::PreintegratedCombinedMeasurements const&) (/usr/local/lib/libgtsam.so.4+0x30e581)
Expected behavior
No problems with the sanitizer in release.
Questions/next steps
I expect it works in Debug because it (probably?) prevents Eigen from doing its fancy alignment-moves..
Is the inconsistent use of EIGEN_MAKE_ALIGNED_OPERATOR_NEW
with a purpose throughout GTSAM? If not, I am ok with working through as much of GTSAM as I can and add many of these Eigen-flags where appropriate. But I'd like some of your thoughts before I start a million-changes approach.
Any other ideas or clues?