Skip to content

Commit 69f78ce

Browse files
authored
Disable mem-access warnings on aarch64. (#506)
* Disable mem-access warnings on aarch64. There is currently a bug in Eigen in Ubuntu 22.04 meaning that it throws a mem-access warning every time Eigen/PacketMath.h is used. There is an upstream fix for it, and we are trying to get that into Ubuntu 22.04, but that is not guaranteed. For now, disable the warning only if we are on GCC. Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
1 parent 7e70fbd commit 69f78ce

File tree

2 files changed

+26
-0
lines changed

2 files changed

+26
-0
lines changed

tf2_eigen/test/tf2_eigen-test.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,20 @@
3737
#include <cmath>
3838
#include <memory>
3939

40+
// Version 3.4.0 of Eigen in Ubuntu 22.04 has a bug that causes -Wclass-memaccess warnings on
41+
// aarch64. Upstream Eigen has already fixed this in
42+
// https://gitlab.com/libeigen/eigen/-/merge_requests/645 . The Debian fix for this is in
43+
// https://salsa.debian.org/science-team/eigen3/-/merge_requests/1 .
44+
// However, it is not clear that that fix is going to make it into Ubuntu 22.04 before it
45+
// freezes, so disable the warning here.
46+
#ifdef __GNUC__
47+
#pragma GCC diagnostic push
48+
#pragma GCC diagnostic ignored "-Wclass-memaccess"
49+
#endif
4050
#include <Eigen/Geometry> // NOLINT
51+
#ifdef __GNUC__
52+
#pragma GCC diagnostic pop
53+
#endif
4154

4255
#include "gtest/gtest.h"
4356

tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,21 @@
3131

3232
#include <string>
3333

34+
// Version 3.4.0 of Eigen in Ubuntu 22.04 has a bug that causes -Wclass-memaccess warnings on
35+
// aarch64. Upstream Eigen has already fixed this in
36+
// https://gitlab.com/libeigen/eigen/-/merge_requests/645 . The Debian fix for this is in
37+
// https://salsa.debian.org/science-team/eigen3/-/merge_requests/1 .
38+
// However, it is not clear that that fix is going to make it into Ubuntu 22.04 before it
39+
// freezes, so disable the warning here.
40+
#ifdef __GNUC__
41+
#pragma GCC diagnostic push
42+
#pragma GCC diagnostic ignored "-Wclass-memaccess"
43+
#endif
3444
#include <Eigen/Eigen> // NOLINT
3545
#include <Eigen/Geometry> // NOLINT
46+
#ifdef __GNUC__
47+
#pragma GCC diagnostic pop
48+
#endif
3649

3750
#include "tf2_ros/buffer_interface.h"
3851

0 commit comments

Comments
 (0)