<br><br><div class="gmail_quote">On Tue, Nov 9, 2010 at 3:10 PM, Daniel Stonier <span dir="ltr"><<a href="mailto:d.stonier@gmail.com">d.stonier@gmail.com</a>></span> wrote:<br><blockquote class="gmail_quote" style="margin: 0pt 0pt 0pt 0.8ex; border-left: 1px solid rgb(204, 204, 204); padding-left: 1ex;">

I think Josh answered some of your more nodelet related questions, so<br>
I'll just respond to your roslaunch queries since I've been running<br>
similar scenarios (1 nodelet manager, about 10 nodelets loading into<br>
it).<br>
<div><div></div><div class="h5"><br>
On 9 November 2010 23:54, Jack O'Quin <<a href="mailto:jack.oquin@gmail.com">jack.oquin@gmail.com</a>> wrote:<br>
> I am experimenting with using nodelets for Velodyne 3D LIDAR support<br>
> on C-turtle. So far, converting the code has been relatively<br>
> straightforward. But, there are some questions I can't answer.<br>
><br>
>  * How do I launch a nodelet manager and several nodelets with roslaunch?<br>
><br>
> The example in the tutorial seems to have no interdependencies or timing issues.<br>
><br>
>  <a href="http://www.ros.org/wiki/nodelet/Tutorials/Running%20a%20nodelet#Using_withing_roslaunch_files" target="_blank">http://www.ros.org/wiki/nodelet/Tutorials/Running%20a%20nodelet#Using_withing_roslaunch_files</a><br>


><br>
> But, when I try to launch my driver nodelet along with a point cloud<br>
> nodelet that converts the raw scan data into ROS<br>
> sensor_msgs/PointCloud format, I seem to get startup sequencing<br>
> problems depending on the order in which things initialize. Sometimes<br>
> it works and sometimes no point cloud gets published. Here is a simple<br>
> example:<br>
><br>
> <launch><br>
>  <node pkg="nodelet" type="nodelet" name="velodyne_nodelet_manager"<br>
>        args="manager" /><br>
>  <node pkg="nodelet" type="nodelet" name="driver_nodelet"<br>
>        args="load velodyne_common/DriverNodelet velodyne_nodelet_manager" /><br>
>  <node pkg="nodelet" type="nodelet" name="pointcloud_nodelet"<br>
>        args="load velodyne_common/PointCloudNodelet<br>
> velodyne_nodelet_manager" /><br>
> </launch><br>
><br>
> I guess a "nodelet load" command sometimes arrives before the "nodelet<br>
> manager" is ready. Since roslaunch makes no guarantees about order, I<br>
> wonder how to solve it. I see no similar problems when dealing with<br>
> the node-based versions of these programs.<br>
<br>
</div></div>No prioritised sequencing in roslaunch causes me a headache too,<br>
though I've never had a situation when the nodelet manager didn't<br>
launch before all my nodelets (I guess because its first in line in my<br>
launcher).<br>
<br></blockquote><div>Nodelet launchers wait to connect with the manager on a wait_for_service such that they will wait for the manager to come up before trying to load their code nodelet.<br><br><br></div><blockquote class="gmail_quote" style="margin: 0pt 0pt 0pt 0.8ex; border-left: 1px solid rgb(204, 204, 204); padding-left: 1ex;">


I do have other sequencing problems though and the only way around it<br>
for now that I know of is to have multiple stage launchers. That<br>
starts getting pretty messy though. It would be more efficient and<br>
simpler if we had a mechanism in roslaunch for this.<br>
<div class="im"><br>
> Shutting down this nodelet manager process has also been unreliable.<br>
> Sometimes the threads with go away with ^C (INTERRUPT), but they often<br>
> hang and require a ^\ (TERMINATE). This may also be an issue with the<br>
> order in which the signals get delivered and processed. Shutting down<br>
> the node-based version works reliably.<br>
<br>
</div>That one's actually not a critical bug, but its a bit annoying having<br>
to wait around for the terminate to arrive. Problem is the nodelets<br>
try and unload themselves on completion, but oft times roslaunch has<br>
killed off the manager, so they can't communicate. You can fix it by<br>
hacking the nodelet source nodelet/src/nodelet.cpp. Cturtle and latest<br>
have similar code (last time I checked), and down near the end in main<br>
there's a block of code that looks like:<br>
<br>
  else if (command == "load")<br>
  {<br>
    ros::init (argc, argv, arg_parser.getDefaultName (),<br>
ros::init_options::NoSigintHandler);<br>
    NodeletInterface ni;<br>
    ros::NodeHandle nh;<br>
    std::string name = ros::this_node::getName ();<br>
    std::string type = arg_parser.getType();<br>
    std::string manager = arg_parser.getManager();<br>
    ni.loadNodelet (name, type, manager, arg_parser.getMyArgv ());<br>
    signal (SIGINT, nodeletLoaderSigIntHandler);<br>
    // Spin our own loop<br>
    while (nh.ok ())<br>
    {<br>
      // ros::spinOnce ();<br>
      if (request_shutdown)<br>
      {<br>
        //ni.unloadNodelet (name, manager);<br>
        ros::shutdown ();<br>
        break;<br>
      }<br>
      usleep(100000);<br>
      sleep(2);<br>
    }<br>
  }<br>
<br>
You'll notice I commented out the<br>
<br>
//ni.unloadNodelet (name, manager);<br>
<br>
line. It doesn't have any side effects as the manager automatically<br>
makes sure the loaded nodelets destruct gracefully anyway.  Should<br>
probably send in a patch for this one.<br>
<div><div></div><div class="h5">_______________________________________________<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><br clear="all"><br>-- <br>Tully Foote<br>Systems Engineer<br>Willow Garage, Inc.<br><a href="mailto:tfoote@willowgarage.com">tfoote@willowgarage.com</a><br>(650) 475-2827<br>