ADVRHumanoids / XBotControl

XBotControl framework: XBotCore + OpenSoT + CartesI/O
33 stars 3 forks source link

segment fault when running XBotCore -D #27

Closed XinyuanZhao closed 4 years ago

XinyuanZhao commented 4 years ago

I run XBotCore -D on Centauro with my config file /home/embedded/catkin_centauro_ws/src/centauro/CentauroConfig/centauro_demo.ymal but a segment fault was prompted and the running crashed. Could you please help to check what accounts for this issue at your convenience? @liesrock

liesrock commented 4 years ago

Hi @XinyuanZhao: this issue is specifically related to Centauro, since the software itself works in simulation, please open the issue in the right repo (i.e. here https://github.com/ADVRHumanoids/CENTAURO-status/issues)

When you have segfault running the dummy using your config file, it means that one of your plugin is segfaulting in the initialization: it is easy to debug what is going on using GDB (refer to this https://www.gnu.org/software/gdb/)

In this case just running:

gdb --args XBotCore -D

gave me the following output:

#0  0x00007ffff6919522 in Eigen::internal::gemm_pack_rhs<double, long, Eigen::internal::const_blas_data_mapper<double, long, 0>, 4, 0, false, false>::operator() (this=<optimized out>, 
    blockB=0x7ffff7e2fa80, rhs=..., depth=144, cols=144, stride=<optimized out>, offset=0)
    at /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h:2088
#1  0x00007fffe815057c in Eigen::internal::general_matrix_matrix_triangular_product<long, double, 0, false, double, 0, false, 0, 2, 0>::run (size=48, depth=148, _lhs=0x7fffc04c7660, 
    lhsStride=48, _rhs=0x7fffc04b9850, rhsStride=148, _res=0x7fffc0048c70, resStride=48, 
    alpha=@0x7ffff7e4ad20: 1)
    at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h:93
#2  0x00007fffe81472c8 in Eigen::general_product_to_triangular_selector<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, 2, false>::run (alpha=<optimized out>, prod=..., mat=...)
    at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h:259
#3  Eigen::TriangularViewImpl<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u, Eigen::Dense>::_assignProduct<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (alpha=<optimized out>, prod=..., this=<optimized out>)
    at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h:275
#4  Eigen::internal::Assignment<Eigen::TriangularView<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::internal::assign_op<double>, Eigen::internal::Dense2Triangular, double>::run (src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h:948
#5  Eigen::internal::call_assignment_no_alias<Eigen::TriangularView<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::internal::assign_op<double> > (func=..., src=..., dst=...)
    at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747
#6  Eigen::TriangularViewImpl<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u, Eigen::Dense>::operator=<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (other=..., this=0x7ffff7e4ad10)
    at /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h:556
#7  OpenSoT::solvers::iHQP::computeCostFunction (this=this@entry=0x7fffc0048a00, task=..., 
    H=..., g=...) at /home/embedded/advr-superbuild/external/OpenSoT/src/solvers/iHQP.cpp:152
#8  0x00007fffe8148330 in OpenSoT::solvers::iHQP::prepareSoT (this=this@entry=0x7fffc0048a00, 
    be_solver=std::vector of length 1, capacity 1 = {...})
    at /home/embedded/advr-superbuild/external/OpenSoT/src/solvers/iHQP.cpp:183
#9  0x00007fffe814baca in OpenSoT::solvers::iHQP::iHQP (this=0x7fffc0048a00, 
    stack_of_tasks=std::vector of length 1, capacity 1 = {...}, bounds=..., 
    eps_regularisation=<optimized out>, be_solver=OpenSoT::solvers::solver_back_ends::qpOASES)
    at /home/embedded/advr-superbuild/external/OpenSoT/src/solvers/iHQP.cpp:78
---Type <return> to continue, or q <return> to quit---
#10 0x00007fffe842bfa8 in boost::make_shared<OpenSoT::solvers::iHQP, std::vector<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, std::allocator<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > > >&, boost::shared_ptr<OpenSoT::Constraint<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, double&, OpenSoT::solvers::solver_back_ends&>(std::vector<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, std::allocator<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > > >&, boost::shared_ptr<OpenSoT::Constraint<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >&&, double&, OpenSoT::solvers::solver_back_ends&) ()
    at /usr/include/boost/smart_ptr/make_shared_object.hpp:254
#11 0x00007fffe84275e2 in legged_robot::OpensotIK::OpensotIK (this=0x7fffc027cf60, model=..., q_initial=..., 
    end_effector_names=<error reading variable: access outside bounds of object referenced via synthetic pointer>, 
    assigned_joint_ids=std::map with 0 elements, control_frequency=<optimized out>)
    at /home/embedded/src/catkin_yangwei_locomotor/src/centauro_yangwei_locomotor/src/inverse_kinematics/opensot_ik.cpp:97
#12 0x00007fffe841157b in XBotPlugin::centauro_yangwei_locomotor::init_control_plugin (this=0x7fffd47ca940, 
    handle=<optimized out>)
    at /home/embedded/src/catkin_yangwei_locomotor/src/centauro_yangwei_locomotor/src/centauro_yangwei_locomotor_plugin.cpp:189
#13 0x00007ffff6bbcf7d in XBot::XBotControlPlugin::init (this=0x7fffd47ca940, handle=handle@entry=0x7fffd462b940, 
    name="centauro_yangwei_locomotor", cstatus=std::shared_ptr<XBot::PluginStatus> (use count 3, weak count 0) = {...}, 

    halInterface=std::shared_ptr<HALBase> (use count 9, weak count 0) = {...}, 
    model=std::shared_ptr<XBot::IXBotModel> (empty) = {...})
    at /home/embedded/advr-superbuild/external/XBotCore/src/XBotControlPlugin.cpp:63

#14 0x00007ffff6bc257b in XBot::PluginHandler::initPlugin (this=this@entry=0x7fffd462b940, 
    plugin_ptr=std::shared_ptr<XBot::XBotControlPlugin> (use count 2, weak count 0) = {...}, 
    name="centauro_yangwei_locomotor") at /home/embedded/advr-superbuild/external/XBotCore/src/XBotPluginHandler.cpp:231
#15 0x00007ffff6bc2e6b in XBot::PluginHandler::init_plugins (this=0x7fffd462b940, 
    halInterface=std::shared_ptr<HALBase> (empty) = {...}, model=std::shared_ptr<XBot::IXBotModel> (empty) = {...})
    at /home/embedded/advr-superbuild/external/XBotCore/src/XBotPluginHandler.cpp:324
#16 0x00007ffff6c22012 in Loader::init_internal (this=0x7fffd47d1180)
    at /home/embedded/advr-superbuild/external/XBotCore/src/Loader.cpp:62
#17 0x00007ffff70fb61b in XBot::XBotLoaderThread::th_init (this=0x7fffd47d11e0)
    at /home/embedded/advr-superbuild/external/XBotCore/src/XBotLoaderThread.cpp:77
#18 0x00007ffff6c214b7 in XBot::nrt_thread (th_hook=0x7fffd47d11e0)
    at /home/embedded/advr-superbuild/external/XBotCore/src/XBotNRT_thread.cpp:15
#19 0x00007ffff7bc782c in cobalt_thread_trampoline () from /usr/xenomai/lib/libcobalt.so.2
#20 0x00007ffff779d6ba in start_thread (arg=0x7ffff7e4c700) at pthread_create.c:333
#21 0x00007ffff0eb141d in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:109

Please refer to your supervisors @nkashiri and @ntsagarakis for the usage of the basic tool of the lab.

Regarding the issue you have it is a matter of Xenomai and Eigen (since in standard kernel the situation is good) with memory allocation from my point of view, but I do not know how to help.

XinyuanZhao commented 4 years ago

Hello Luca,

Thank you for your detailed reply.

I will try to debug this issue later by using GDB. What are the "basic tools of the lab" you referred to?

By the way, perhaps I don't have access to the repository "CENTAURO-status" since the linked page is not found.

Best regards Xinyuan

Luca Muratore notifications@github.com 于2019年10月24日周四 上午11:22写道:

Hi @XinyuanZhao https://github.com/XinyuanZhao: this issue is specifically related to Centauro, since the software itself works in simulation, please open the issue in the right repo (i.e. here https://github.com/ADVRHumanoids/CENTAURO-status/issues)

When you have segfault running the dummy using your config file, it means that one of your plugin is segfaulting in the initialization: it is easy to debug what is going on using GDB (refer to this https://www.gnu.org/software/gdb/)

In this case just running:

gdb --args XBotCore -D

gave me the following output:

0 0x00007ffff6919522 in Eigen::internal::gemm_pack_rhs<double, long, Eigen::internal::const_blas_data_mapper<double, long, 0>, 4, 0, false, false>::operator() (this=,

blockB=0x7ffff7e2fa80, rhs=..., depth=144, cols=144, stride=<optimized out>, offset=0)
at /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h:2088

1 0x00007fffe815057c in Eigen::internal::general_matrix_matrix_triangular_product<long, double, 0, false, double, 0, false, 0, 2, 0>::run (size=48, depth=148, _lhs=0x7fffc04c7660,

lhsStride=48, _rhs=0x7fffc04b9850, rhsStride=148, _res=0x7fffc0048c70, resStride=48,
alpha=@0x7ffff7e4ad20: 1)
at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h:93

2 0x00007fffe81472c8 in Eigen::general_product_to_triangular_selector<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, 2, false>::run (alpha=, prod=..., mat=...)

at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h:259

3 Eigen::TriangularViewImpl<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u, Eigen::Dense>::_assignProduct<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (alpha=, prod=..., this=)

at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h:275

4 Eigen::internal::Assignment<Eigen::TriangularView<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::internal::assign_op, Eigen::internal::Dense2Triangular, double>::run (src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h:948

5 Eigen::internal::call_assignment_no_alias<Eigen::TriangularView<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::internal::assign_op > (func=..., src=..., dst=...)

at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747

6 Eigen::TriangularViewImpl<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2u, Eigen::Dense>::operator=<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (other=..., this=0x7ffff7e4ad10)

at /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h:556

7 OpenSoT::solvers::iHQP::computeCostFunction (this=this@entry=0x7fffc0048a00, task=...,

H=..., g=...) at /home/embedded/advr-superbuild/external/OpenSoT/src/solvers/iHQP.cpp:152

8 0x00007fffe8148330 in OpenSoT::solvers::iHQP::prepareSoT (this=this@entry=0x7fffc0048a00,

be_solver=std::vector of length 1, capacity 1 = {...})
at /home/embedded/advr-superbuild/external/OpenSoT/src/solvers/iHQP.cpp:183

9 0x00007fffe814baca in OpenSoT::solvers::iHQP::iHQP (this=0x7fffc0048a00,

stack_of_tasks=std::vector of length 1, capacity 1 = {...}, bounds=...,
eps_regularisation=<optimized out>, be_solver=OpenSoT::solvers::solver_back_ends::qpOASES)
at /home/embedded/advr-superbuild/external/OpenSoT/src/solvers/iHQP.cpp:78

---Type to continue, or q to quit---

10 0x00007fffe842bfa8 in boost::make_shared<OpenSoT::solvers::iHQP, std::vector<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, std::allocator<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > > >&, boost::shared_ptr<OpenSoT::Constraint<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, double&, OpenSoT::solvers::solver_back_ends&>(std::vector<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, std::allocator<boost::shared_ptr<OpenSoT::Task<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > > >&, boost::shared_ptr<OpenSoT::Constraint<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >&&, double&, OpenSoT::solvers::solver_back_ends&) ()

at /usr/include/boost/smart_ptr/make_shared_object.hpp:254

11 0x00007fffe84275e2 in legged_robot::OpensotIK::OpensotIK (this=0x7fffc027cf60, model=..., q_initial=...,

end_effector_names=<error reading variable: access outside bounds of object referenced via synthetic pointer>,
assigned_joint_ids=std::map with 0 elements, control_frequency=<optimized out>)
at /home/embedded/src/catkin_yangwei_locomotor/src/centauro_yangwei_locomotor/src/inverse_kinematics/opensot_ik.cpp:97

12 0x00007fffe841157b in XBotPlugin::centauro_yangwei_locomotor::init_control_plugin (this=0x7fffd47ca940,

handle=<optimized out>)
at /home/embedded/src/catkin_yangwei_locomotor/src/centauro_yangwei_locomotor/src/centauro_yangwei_locomotor_plugin.cpp:189

13 0x00007ffff6bbcf7d in XBot::XBotControlPlugin::init (this=0x7fffd47ca940, handle=handle@entry=0x7fffd462b940,

name="centauro_yangwei_locomotor", cstatus=std::shared_ptr<XBot::PluginStatus> (use count 3, weak count 0) = {...},

halInterface=std::shared_ptr<HALBase> (use count 9, weak count 0) = {...},
model=std::shared_ptr<XBot::IXBotModel> (empty) = {...})
at /home/embedded/advr-superbuild/external/XBotCore/src/XBotControlPlugin.cpp:63

14 0x00007ffff6bc257b in XBot::PluginHandler::initPlugin (this=this@entry=0x7fffd462b940,

plugin_ptr=std::shared_ptr<XBot::XBotControlPlugin> (use count 2, weak count 0) = {...},
name="centauro_yangwei_locomotor") at /home/embedded/advr-superbuild/external/XBotCore/src/XBotPluginHandler.cpp:231

15 0x00007ffff6bc2e6b in XBot::PluginHandler::init_plugins (this=0x7fffd462b940,

halInterface=std::shared_ptr<HALBase> (empty) = {...}, model=std::shared_ptr<XBot::IXBotModel> (empty) = {...})
at /home/embedded/advr-superbuild/external/XBotCore/src/XBotPluginHandler.cpp:324

16 0x00007ffff6c22012 in Loader::init_internal (this=0x7fffd47d1180)

at /home/embedded/advr-superbuild/external/XBotCore/src/Loader.cpp:62

17 0x00007ffff70fb61b in XBot::XBotLoaderThread::th_init (this=0x7fffd47d11e0)

at /home/embedded/advr-superbuild/external/XBotCore/src/XBotLoaderThread.cpp:77

18 0x00007ffff6c214b7 in XBot::nrt_thread (th_hook=0x7fffd47d11e0)

at /home/embedded/advr-superbuild/external/XBotCore/src/XBotNRT_thread.cpp:15

19 0x00007ffff7bc782c in cobalt_thread_trampoline () from /usr/xenomai/lib/libcobalt.so.2

20 0x00007ffff779d6ba in start_thread (arg=0x7ffff7e4c700) at pthread_create.c:333

21 0x00007ffff0eb141d in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:109

Please refer to your supervisors @nkashiri https://github.com/nkashiri and @ntsagarakis https://github.com/ntsagarakis for the usage of the basic tool of the lab.

Regarding the issue you have it is a matter of Xenomai and Eigen (since in standard kernel the situation is good) with memory allocation from my point of view, but I do not know how to help.

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/ADVRHumanoids/XBotControl/issues/27?email_source=notifications&email_token=AGAY4QBLUBTRKK5NSH3ZAWLQQFSPDA5CNFSM4JECL5K2YY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGOECELGJQ#issuecomment-545829670, or unsubscribe https://github.com/notifications/unsubscribe-auth/AGAY4QAFOL53JWCMZMVE6O3QQFSPDANCNFSM4JECL5KQ .

liesrock commented 4 years ago

@XinyuanZhao you are already part of the @ADVRHumanoids/all team, so you should be able to see this repo https://github.com/ADVRHumanoids/CENTAURO-status