Looks like it's because you're not calling ros::shutdown() before you unload the plugin.<div><br></div><div>Josh<br><br><div class="gmail_quote">On Sun, Sep 12, 2010 at 5:59 AM, Ruben Smits <span dir="ltr"><<a href="mailto:ruben.smits@mech.kuleuven.be">ruben.smits@mech.kuleuven.be</a>></span> wrote:<br>

<blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;"><div class="im">On Saturday 11 September 2010 20:03:48 Josh Faust wrote:<br>
> init() shouldn't be blocking -- if it does it's a bug.  It's designed this<br>
> way so you can call ros::master::check().  Creation of the first<br>
> NodeHandle or calling start() should be what's blocking.<br>
<br>
</div>Ok, sorry for the mistake, it was indeed ros::start() that blocked my code. I<br>
changed it into the following:<br>
<br>
bool loadRTTPlugin(RTT::TaskContext* c){<br>
    log(Info)<<"Initializing ROS node"<<endlog();<br>
    if(!ros::isInitialized()){<br>
      int argc=0;<br>
      char* argv[0];<br>
      ros::init(argc,argv,"rtt",ros::init_options::AnonymousName);<br>
      if(ros::master::check())<br>
          ros::start();<br>
      else{<br>
          log(Error)<<"No ros::master available"<<endlog();<br>
          return false;<br>
      }<br>
    }<br>
    static ros::AsyncSpinner spinner(1); // Use 1 threads<br>
    spinner.start();<br>
    log(Info)<<"ROS node spinner started"<<endlog();<br>
    return true;<br>
  }<br>
<br>
But now I get the the following assertion:<br>
<br>
0.719 [ ERROR  ][DeploymentComponent::import] No ros::master available<br>
0.719 [ ERROR  ][DeploymentComponent::import] Failed to load RTT Plugin<br>
'ros_integration': plugin refused to load into this process. Unloading.<br>
deployer-gnulinux: /usr/include/boost/thread/pthread/mutex.hpp:50: void<br>
boost::mutex::lock(): Assertion `!pthread_mutex_lock(&m)' failed.<br>
<br>
Program received signal SIGABRT, Aborted.<br>
0x00007ffff4caca75 in *__GI_raise (sig=<value optimized out>)<br>
    at ../nptl/sysdeps/unix/sysv/linux/raise.c:64<br>
64      ../nptl/sysdeps/unix/sysv/linux/raise.c: No such file or directory.<br>
        in ../nptl/sysdeps/unix/sysv/linux/raise.c<br>
(gdb) bt<br>
#0  0x00007ffff4caca75 in *__GI_raise (sig=<value optimized out>)<br>
    at ../nptl/sysdeps/unix/sysv/linux/raise.c:64<br>
#1  0x00007ffff4cb05c0 in *__GI_abort () at abort.c:92<br>
#2  0x00007ffff4ca5941 in *__GI___assert_fail (<br>
    assertion=0x7ffff124f7e5 "!pthread_mutex_lock(&m)",<br>
    file=<value optimized out>, line=50,<br>
    function=0x7ffff124f9a0 "void boost::mutex::lock()") at assert.c:81<br>
#3  0x00007ffff12453db in boost::mutex::lock (loc=0x7ffff1beea20,<br>
    name=..., level=ros::console::levels::Debug)<br>
    at /usr/include/boost/thread/pthread/mutex.hpp:50<br>
#4  boost::unique_lock<boost::mutex>::lock (loc=0x7ffff1beea20, name=...,<br>
    level=ros::console::levels::Debug)<br>
    at /usr/include/boost/thread/locks.hpp:338<br>
#5  unique_lock (loc=0x7ffff1beea20, name=...,<br>
    level=ros::console::levels::Debug)<br>
    at /usr/include/boost/thread/locks.hpp:224<br>
#6  ros::console::initializeLogLocation (loc=0x7ffff1beea20, name=...,<br>
    level=ros::console::levels::Debug)<br>
    at /opt/ros/cturtle/ros/core/rosconsole/src/rosconsole/rosconsole.cpp:6---<br>
Type <return> to continue, or q <return> to quit---<br>
10<br>
#7  0x00007ffff1923e4a in ros::atexitCallback ()<br>
    at /opt/ros/cturtle/ros/core/roscpp/src/libros/init.cpp:149<br>
#8  0x00007ffff4cb2630 in __cxa_finalize (d=0x7ffff1bee000)<br>
    at cxa_finalize.c:56<br>
#9  0x00007ffff18f23d6 in __do_global_dtors_aux ()<br>
   from /opt/ros/cturtle/ros/core/roscpp/lib/libros.so<br>
#10 0x0000000000000015 in ?? ()<br>
#11 0x00007fffffffc8d0 in ?? ()<br>
#12 0x00007ffff19abc81 in _fini ()<br>
   from /opt/ros/cturtle/ros/core/roscpp/lib/libros.so<br>
#13 0x0000000000000032 in ?? ()<br>
#14 0x00007ffff7df0972 in _dl_close_worker (map=<value optimized out>)<br>
    at dl-close.c:271<br>
#15 0x0000000000680f80 in ?? ()<br>
<br>
Another question:<br>
<br>
Would it be possible to start my own master if none is available? Can it be<br>
done using ros::master::init()?<br>
<br>
Ruben<br>
<div class="im">> Josh<br>
><br>
> On Sat, Sep 11, 2010 at 7:53 AM, Ruben Smits<br>
</div><div class="im">> <<a href="mailto:ruben.smits@mech.kuleuven.be">ruben.smits@mech.kuleuven.be</a><mailto:<a href="mailto:ruben.smits@mech.kuleuven.be">ruben.smits@mech.kuleuven.be</a>>> wrote:<br>
> Hi,<br>
><br>
> I would like to know if there is a way to call ros::init and not block<br>
> untill a ros::master is available but just return an error or the like if<br>
> a ros::master is not available so that my code can continue.<br>
><br>
> Ruben<br>
> _______________________________________________<br>
> ros-users mailing list<br>
</div>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><mailto:<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a>><br>
<div><div></div><div class="h5">> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
</div></div></blockquote></div><br></div>