Apollo里频繁发生Eigen库相关的崩溃的解决办法

Eigen崩溃的原因多和地址对齐问题有关,常见的几种造成地址对齐问题的原因在Eigen的官方文档这里有说明:Eigen: Explanation of the assertion on unaligned arrays

我使用Apollo9早期版本崩溃的经历里,多次是属于第一种"Structures having Eigen objects as members" 在Structure里加上

     public:

        EIGEN_MAKE_ALIGNED_OPERATOR_NEW

即可解决问题,少数特殊情况,加上了上面的宏定义也没用,照样崩溃在Structure的构造函数里,例如:

mainboard: external/uuid/eigen3/Eigen/src/Core/DenseStorage.h:128: Eigen::internal::plain_array<T, Size, MatrixOrArrayOptions, 32>::plain_array() [with T = double; int Size = 16; int MatrixOrArrayOptions = 0]: Assertion `(internal::UIntPtr(eigen_unaligned_array_assert_workaround_gcc47(array)) & (31)) == 0 && "this assertion is explained here: " "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" " **** READ THIS WEB PAGE !!! ****"' failed.

Thread 8 "mainboard" received signal SIGABRT, Aborted.

#0  0x00007fffeb205e87 in raise () at /lib/x86_64-linux-gnu/libc.so.6
#1  0x00007fffeb2077f1 in abort () at /lib/x86_64-linux-gnu/libc.so.6
#2  0x00007fffeb1f73fa in  () at /lib/x86_64-linux-gnu/libc.so.6
#3  0x00007fffeb1f7472 in  () at /lib/x86_64-linux-gnu/libc.so.6
#4  0x00007fffae3ab64f in Eigen::internal::plain_array<double, 16, 0, 32>::plain_array() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#5  0x00007fffae3a23ae in Eigen::DenseStorage<double, 16, 4, 4, 0>::DenseStorage() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#6  0x00007fffae3a4040 in Eigen::PlainObjectBase<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::PlainObjectBase() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#7  0x00007fffae39a8c4 in Eigen::Matrix<double, 4, 4, 0, 4, 4>::Matrix() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#8  0x00007fffae39b16a in Eigen::Transform<double, 3, 2, 0>::Transform<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > >(Eigen::EigenBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > > const&) ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#9  0x00007fffae3933dd in Eigen::Transform<double, 3, 2, 0>::Identity() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#10 0x00007fffae3d1beb in apollo::perception::onboard::CameraFrame::CameraFrame() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#11 0x00007fffae3d1c76 in void __gnu_cxx::new_allocator<apollo::perception::onboard::CameraFrame>::construct<apollo::perception::onboard::CameraFrame>(apollo::perception::onboard::CameraFrame*) () at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#12 0x00007fffae3cb48f in void std::allocator_traits<std::allocator<apollo::perception::onboard::CameraFrame> >::construct<apollo::perception::onboard::CameraFrame>(std::allocator<apollo::perception::onboard::CameraFrame>&, apollo::perception::onboard::CameraFrame*) ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#13 0x00007fffae3c41ad in std::_Sp_counted_ptr_inplace<apollo::perception::onboard::CameraFrame, std::allocator<apollo::perception::onboard::CameraFrame>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<>(std::allocator<apollo::perception::onboard::CameraFrame>) ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#14 0x00007fffae3bcf3e in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<apollo::perception::onboard::CameraFrame, std::allocator<apollo::perception::onboard::CameraFrame>>(std::_Sp_make_shared_tag, apollo::perception::onboard::CameraFrame*, std::allocator<apollo::perception::onboard::CameraFrame> const&) () at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#15 0x00007fffae3b3a62 in std::__shared_ptr<apollo::perception::onboard::CameraFrame, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<apollo::perception::onboard::CameraFrame>>(std::_Sp_make_shared_tag, std::allocator<apollo::perception::onboard::CameraFrame> const&) ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#16 0x00007fffae3a84bc in std::shared_ptr<apollo::perception::onboard::CameraFrame>::shared_ptr<std::allocator<apollo::perception::onboard::CameraFrame>>(std::_Sp_make_shared_tag, std::allocator<apollo::perception::onboard::CameraFrame> const&) ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#17 0x00007fffae39de77 in std::shared_ptr<apollo::perception::onboard::CameraFrame> std::allocate_shared<apollo::perception::onboard::CameraFrame, std::allocator<apollo::perception::onboard::CameraFrame>>(std::allocator<apollo::perception::onboard::CameraFrame> const&) ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#18 0x00007fffae39560c in std::shared_ptr<apollo::perception::onboard::CameraFrame> std::make_shared<apollo::perception::onboard::CameraFrame>() ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#19 0x00007fffae37ea24 in apollo::perception::camera::CameraDetectionStreamPETRComponent::OnReceiveImage(std::shared_ptr<apollo::drivers::CompressedImage> const&) () at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so
#20 0x00007fffae37d20e in apollo::perception::camera::CameraDetectionStreamPETRComponent::InitListeners(apollo::perception::camera::CameraDetectionStreamPETR const&)::{lambda(std::shared_ptr<apollo::drivers::CompressedImage> const&)#1}::operator()(std::shared_ptr<apollo::drivers::CompressedImage> const&) const ()
    at /apollo/bazel-bin/modules/perception/camera_detection_streampetr/libcamera_detection_streampetr_component.so

上面的崩溃就发生在CameraFrame的构造函数里,但是看Apollo9源码里/apollo/modules/perception/common/onboard/inner_component_messages/camera_detection_component_messages.h里关于CameraFrame的定义似乎没什么问题(Apollo9最新的代码里这个文件的内容仍然没什么变化):

namespace apollo {
namespace perception {
namespace onboard {

struct CameraFrame {


  // Frame sequence id
  std::uint64_t frame_id;
  // Timestamp
  double timestamp;
  // Image
  std::shared_ptr<camera::DataProvider> data_provider;
  // Detection result
  std::vector<base::ObjectPtr> detected_objects;
  // appearance features for tracking
  std::shared_ptr<base::Blob<float>> feature_blob = nullptr;
  // intrinstic

  Eigen::Matrix3f camera_k_matrix = Eigen::Matrix3f::Identity();
  // camera to world pose
  Eigen::Affine3d camera2world_pose = Eigen::Affine3d::Identity();

  public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

};

}  // namespace onboard
}  // namespace perception
}  // namespace apollo

但是运行我自己写的component时总是崩溃在CameraFrame的构造函数里:apollo::perception::onboard::CameraFrame::CameraFrame()

我有同事恰好之前遇到了这个问题并且对代码稍做了点修改,对出错的地方的class定义强制不做地址对齐,就不崩溃了:

也就是把

        Eigen::Affine3d camera2world_pose = Eigen::Affine3d::Identity();

改成

       Eigen::Transform<double,3,2,Eigen::DontAlign> camera2world_pose = Eigen::Affine3d::Identity();

从上面的出错可以看出

      Eigen::Affine3d::Identity()

等同于

     Eigen::Transform<double, 3, 2, 0>::Identity()

因此,只需用Eigen::Transform<double,3,2,Eigen::DontAlign>替代掉Eigen::Afine3d即可

为何Structure在加了EIGEN_MAKE_ALIGNED_OPERATOR_NEW声明后仍然崩溃?这种问题表现不符合官网上列出的四种类型中的任何一种,我猜测原因应该是在编译Apollo时为了节省时间只做部分编译造成的或者Apollo所需的支持库造成的地址不对,类似有人调用Open3D时发现的这个问题,也是通过强制不做地址对齐来解决: https://github.com/isl-org/Open3D/issues/653

【SCI复现】含可再生能源与储能的区域微电网最优运行:应对不确定性的解鲁棒性与非预见性研究(Matlab代码实现)内容概要:本文围绕含可再生能源与储能的区域微电网最优运行展开研究,重点探讨应对不确定性的解鲁棒性与非预见性策略,通过Matlab代码实现SCI论文复现。研究涵盖多阶段鲁棒调度模型、机会约束规划、需求响应机制及储能系统优化配置,结合风电、光伏等可再生能源出力的不确定性建模,提出兼顾系统经济性与鲁棒性的优化运行方案。文中详细展示了模型构建、算法设计(如C&CG算法、大M法)及仿真验证全过程,适用于微电网能量管理、电力系统优化调度等领域的科研与工程实践。; 适合人群:具备一定电力系统、优化理论和Matlab编程基础的研究生、科研人员及从事微电网、能源管理相关工作的工程技术人员。; 使用场景及目标:①复现SCI级微电网鲁棒优化研究成果,掌握应对风光负荷不确定性的建模与求解方法;②深入理解两阶段鲁棒优化、分布鲁棒优化、机会约束规划等先进优化方法在能源系统中的实际应用;③为撰写高水平学术论文或开展相关课题研究提供代码参考和技术支持。; 阅读建议:建议读者结合文档提供的Matlab代码逐模块学习,重点关注不确定性建模、鲁棒优化模型构建与求解流程,并尝试在不同场景下调试与扩展代码,以深化对微电网优化运行机制的理解。
评论
成就一亿技术人!
拼手气红包6.0元
还能输入1000个字符
 
红包 添加红包
表情包 插入表情
 条评论被折叠 查看
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Arnold-FY-Chen

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值