Open Shaquille-Wu opened 2 years ago
Describe the bug PlaneMotion里面有一个成员: base::MotionType mat_motionsensor 这里的MotionType是一个Eigen::Matrix4f,需要32字节对齐,目前的运行时出现错误信息如下: libc.so.6!raise (Unknown Source:0) libc.so.6!abort (Unknown Source:0) libc.so.6![Unknown/Just-In-Time compiled code] (Unknown Source:0) libc.so.6!assert_fail (Unknown Source:0) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::internal::plain_array<float, 16, 0, 32>::plain_array(Eigen::internal::plain_array<float, 16, 0, 32> const this) (\proc\self\cwd\external\eigen\Eigen\src\Core\DenseStorage.h:128) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::DenseStorage<float, 16, 4, 4, 0>::DenseStorage(Eigen::DenseStorage<float, 16, 4, 4, 0> const this) (\proc\self\cwd\external\eigen\Eigen\src\Core\DenseStorage.h:187) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::PlainObjectBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> >::PlainObjectBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > >(Eigen::PlainObjectBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const this, const Eigen::DenseBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > > & other) (\proc\self\cwd\external\eigen\Eigen\src\Core\PlainObjectBase.h:533) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::Matrix<float, 4, 4, 0, 4, 4>::Matrix<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > >(Eigen::Matrix<float, 4, 4, 0, 4, 4> const this, const Eigen::EigenBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > > & other) (\proc\self\cwd\external\eigen\Eigen\src\Core\Matrix.h:377) libmodules_Sperception_Scamera_Slib_Smotion_Slibmotion.so!apollo::perception::camera::PlaneMotion::PlaneMotion(apollo::perception::camera::PlaneMotion const this, int s) (\apollo\modules\perception\camera\lib\motion\plane_motion.cc:28) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!apollo::perception::camera::MotionService::Init(apollo::perception::camera::MotionService const this) (\apollo\modules\perception\camera\lib\motion_service\motion_service.cc:36) apollo::cyber::Component<apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType>::Initialize(apollo::cyber::Component<apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType> const this, const apollo::cyber::proto::ComponentConfig & config) (\apollo\cyber\component\component.h:198) apollo::cyber::mainboard::ModuleController::LoadModule(apollo::cyber::mainboard::ModuleController const this, const apollo::cyber::proto::DagConfig & dag_config) (\apollo\cyber\mainboard\module_controller.cc:97) apollo::cyber::mainboard::ModuleController::LoadModule(apollo::cyber::mainboard::ModuleController * const this, const std::cxx11::string & path) (\apollo\cyber\mainboard\module_controller.cc:122) apollo::cyber::mainboard::ModuleController::LoadAll(apollo::cyber::mainboard::ModuleController const this) (\apollo\cyber\mainboard\module_controller.cc:66) apollo::cyber::mainboard::ModuleController::Init(apollo::cyber::mainboard::ModuleController const this) (\apollo\cyber\mainboard\module_controller.h:59) main(int argc, char ** argv) (\apollo\cyber\mainboard\mainboard.cc:37)
To Reproduce Steps to reproduce the behavior: /apollo/bazel-bin/cyber/mainboard/mainboard -d /apollo/modules/perception/production/dag/dag_motion_service.dag \ -p nep_motion_service \ -s CYBER_DEFAULT
如果在PlaneMotion类这么修改,则可以规避以上问题: ...... ...... public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW ...... ......
事实上,我在issue里面并没有发现类似的话题,我猜apollo团队自己应该是运行正常的, 其实,我的所有编译、操作都是在apollo官方的docker中执行的,因此我想知道,为什么我这里会出现这个异常
同理,根据eign自己的介绍,有关stl容器内的元素对齐的问题,相应的stl容器在初始化/声明的时候需要符合一定的规范,但是我在apollo里面看到的,至少PlaneMotion里面看到的情况是,并没有做相应的配置,仿佛默认就能满足eign关于对齐的要求。 所以,我想请教一下,apollo为什么不做相应的处理呢?
希望apollo团队能帮我解答以上问题。
Encountered similiar issue when running modules/perception/camera/tools/offline/offline_obstacle_pipeline:
modules/perception/camera/tools/offline/offline_obstacle_pipeline
@Shaquille-Wu it's a bug, we do need align. and eigen use EIGEN_MAKE_ALIGNED_OPERATOR_NEW to align
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Describe the bug PlaneMotion里面有一个成员: base::MotionType mat_motionsensor 这里的MotionType是一个Eigen::Matrix4f,需要32字节对齐,目前的运行时出现错误信息如下: libc.so.6!raise (Unknown Source:0) libc.so.6!abort (Unknown Source:0) libc.so.6![Unknown/Just-In-Time compiled code] (Unknown Source:0) libc.so.6!assert_fail (Unknown Source:0) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::internal::plain_array<float, 16, 0, 32>::plain_array(Eigen::internal::plain_array<float, 16, 0, 32> const this) (\proc\self\cwd\external\eigen\Eigen\src\Core\DenseStorage.h:128) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::DenseStorage<float, 16, 4, 4, 0>::DenseStorage(Eigen::DenseStorage<float, 16, 4, 4, 0> const this) (\proc\self\cwd\external\eigen\Eigen\src\Core\DenseStorage.h:187) libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::PlainObjectBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> >::PlainObjectBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > >(Eigen::PlainObjectBase<Eigen::Matrix<float, 4, 4, 0, 4, 4> > const this, const Eigen::DenseBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > > & other) (\proc\self\cwd\external\eigen\Eigen\src\Core\PlainObjectBase.h:533)
libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!Eigen::Matrix<float, 4, 4, 0, 4, 4>::Matrix<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > >(Eigen::Matrix<float, 4, 4, 0, 4, 4> const this, const Eigen::EigenBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op, Eigen::Matrix<float, 4, 4, 0, 4, 4> > > & other) (\proc\self\cwd\external\eigen\Eigen\src\Core\Matrix.h:377)
libmodules_Sperception_Scamera_Slib_Smotion_Slibmotion.so!apollo::perception::camera::PlaneMotion::PlaneMotion(apollo::perception::camera::PlaneMotion const this, int s) (\apollo\modules\perception\camera\lib\motion\plane_motion.cc:28)
libmodules_Sperception_Scamera_Slib_Smotion_Uservice_Slibmotion_Uservice_Ulib.so!apollo::perception::camera::MotionService::Init(apollo::perception::camera::MotionService const this) (\apollo\modules\perception\camera\lib\motion_service\motion_service.cc:36)
apollo::cyber::Component<apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType>::Initialize(apollo::cyber::Component<apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType, apollo::cyber::NullType> const this, const apollo::cyber::proto::ComponentConfig & config) (\apollo\cyber\component\component.h:198)
apollo::cyber::mainboard::ModuleController::LoadModule(apollo::cyber::mainboard::ModuleController const this, const apollo::cyber::proto::DagConfig & dag_config) (\apollo\cyber\mainboard\module_controller.cc:97)
apollo::cyber::mainboard::ModuleController::LoadModule(apollo::cyber::mainboard::ModuleController * const this, const std:: cxx11::string & path) (\apollo\cyber\mainboard\module_controller.cc:122)
apollo::cyber::mainboard::ModuleController::LoadAll(apollo::cyber::mainboard::ModuleController const this) (\apollo\cyber\mainboard\module_controller.cc:66)
apollo::cyber::mainboard::ModuleController::Init(apollo::cyber::mainboard::ModuleController const this) (\apollo\cyber\mainboard\module_controller.h:59)
main(int argc, char ** argv) (\apollo\cyber\mainboard\mainboard.cc:37)
To Reproduce Steps to reproduce the behavior: /apollo/bazel-bin/cyber/mainboard/mainboard -d /apollo/modules/perception/production/dag/dag_motion_service.dag \ -p nep_motion_service \ -s CYBER_DEFAULT
如果在PlaneMotion类这么修改,则可以规避以上问题: ...... ...... public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW ...... ......
事实上,我在issue里面并没有发现类似的话题,我猜apollo团队自己应该是运行正常的, 其实,我的所有编译、操作都是在apollo官方的docker中执行的,因此我想知道,为什么我这里会出现这个异常
同理,根据eign自己的介绍,有关stl容器内的元素对齐的问题,相应的stl容器在初始化/声明的时候需要符合一定的规范,但是我在apollo里面看到的,至少PlaneMotion里面看到的情况是,并没有做相应的配置,仿佛默认就能满足eign关于对齐的要求。 所以,我想请教一下,apollo为什么不做相应的处理呢?
希望apollo团队能帮我解答以上问题。