ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Crash when calling init_node while holding GIL

asked 2016-02-26 17:54:50 -0500

inflector gravatar image

I'm getting a crash when trying to invoke rospy from within an embedded Python interpreter.

Ubuntu 14.04LTS Python 2.7.6 rosdistro: jade rosversion: 1.11.16

The following C/C++ file duplicates the problem:

#include <Python.h>

int main(int argc, char* argv[])
{
    Py_InitializeEx(0);
    PyEval_InitThreads();

    static const char *argv0 = "test";
    PySys_SetArgv(1, (char **) &argv0);

    PyEval_ReleaseLock();

    PyGILState_STATE gstate;
    gstate = PyGILState_Ensure();

    PyRun_SimpleString("import rospy");
    printf ("import rospy - successful\n");

    PyRun_SimpleString("rospy.init_node('OpenCog_Eva')");
    PyGILState_Release(gstate);

    Py_Finalize();
    printf ("finished\n");
    return 0;
}

The crashes are of the form:

Fatal Python error: ceval: tstate mix-up
Aborted

or

Segmentation fault

or

Fatal Python error: PyEval_SaveThread: NULL tstate
Aborted

or

Fatal Python error: GC object already tracked
Aborted

These are all problems that come about when the GIL locking isn't quite right.

Any ideas how to fix this crash?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2016-02-26 22:11:46 -0500

linas gravatar image

Found it!! Use PyEval_SaveThread() instead of PyEval_ReleaseLock(). Several websites clearly state that PyEval_ReleaseLock() is to be used, but it seems they're wrong. The official python documentation has a cryptic warning that suggests that using PyEval_SaveThread() is preferred. And indeed, that fixes the bug!

edit flag offensive delete link more

Comments

Interesting, I tried that in the sample and it still crashed.

I needed to do two additional things for the sample:

1) Put a rospy.spin() in somewhere before releasing the GIL.

2) Swap back in the main thread's state with PyThreadState_Swap(thread_state) before Py_Finalize().

inflector gravatar image inflector  ( 2016-02-27 05:52:04 -0500 )edit
0

answered 2016-02-27 06:18:35 -0500

inflector gravatar image

The solution comes in three parts:

1) As per Linas's answer, you need to save the thread state with PyEval_SaveThread()

2) You need to call rospy.spin() before shutting down to give time for all the rospy threads to terminate. If a rospy thread is active when you call Py_Finalize(), you may get a crash.

3) You need to restore the main thread state as saved in 1) above via a call to PyThreadState_Swap before calling Py_Finalize().

The following is a working version of the above sample:

#include <Python.h>

int main(int argc, char* argv[])
{
    Py_InitializeEx(0);
    PyEval_InitThreads();

    static const char *argv0 = "test";
    PySys_SetArgv(1, (char **) &argv0);

    // Call this instead of PyEval_ReleaseLock()
    PyThreadState* thread_state = PyEval_SaveThread() ;

    PyGILState_STATE gstate;
    gstate = PyGILState_Ensure();

    PyRun_SimpleString("import rospy");
    printf ("import rospy - successful\n");

    PyRun_SimpleString("rospy.init_node('OpenCog_Eva')");

    // Make sure the thread doesn't exit before rospy is shutdown.
    PyRun_SimpleString("rospy.spin()");
    PyGILState_Release(gstate);

    // Restore the main thread saved above.
    PyThreadState_Swap(thread_state);

    Py_Finalize();
    printf ("finished\n");
    return 0;
}
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-02-26 17:54:50 -0500

Seen: 696 times

Last updated: Feb 27 '16