diff --git a/mavros/src/plugins/global_position.cpp b/mavros/src/plugins/global_position.cpp index 68983ac59..ca5af5693 100644 --- a/mavros/src/plugins/global_position.cpp +++ b/mavros/src/plugins/global_position.cpp @@ -43,6 +43,8 @@ namespace std_plugins { */ class GlobalPositionPlugin : public plugin::PluginBase { public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GlobalPositionPlugin() : PluginBase(), gp_nh("~global_position"), tf_send(false), diff --git a/mavros/src/plugins/imu.cpp b/mavros/src/plugins/imu.cpp index f1339b3ec..77439dbb2 100644 --- a/mavros/src/plugins/imu.cpp +++ b/mavros/src/plugins/imu.cpp @@ -45,6 +45,8 @@ static constexpr double RAD_TO_DEG = 180.0 / M_PI; //! @brief IMU and attitude data publication plugin class IMUPlugin : public plugin::PluginBase { public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + IMUPlugin() : PluginBase(), imu_nh("~imu"), has_hr_imu(false), diff --git a/mavros/src/plugins/setpoint_position.cpp b/mavros/src/plugins/setpoint_position.cpp index ea2dd6921..ebce51e91 100644 --- a/mavros/src/plugins/setpoint_position.cpp +++ b/mavros/src/plugins/setpoint_position.cpp @@ -38,6 +38,8 @@ class SetpointPositionPlugin : public plugin::PluginBase, private plugin::SetPositionTargetLocalNEDMixin, private plugin::TF2ListenerMixin { public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + SetpointPositionPlugin() : PluginBase(), sp_nh("~setpoint_position"), spg_nh("~"),