[ros-users] questions about nodelets

Tully Foote tfoote at willowgarage.com
Wed Nov 10 00:03:33 UTC 2010


On Tue, Nov 9, 2010 at 3:10 PM, Daniel Stonier <d.stonier at gmail.com> wrote:

> I think Josh answered some of your more nodelet related questions, so
> I'll just respond to your roslaunch queries since I've been running
> similar scenarios (1 nodelet manager, about 10 nodelets loading into
> it).
>
> On 9 November 2010 23:54, Jack O'Quin <jack.oquin at gmail.com> wrote:
> > I am experimenting with using nodelets for Velodyne 3D LIDAR support
> > on C-turtle. So far, converting the code has been relatively
> > straightforward. But, there are some questions I can't answer.
> >
> >  * How do I launch a nodelet manager and several nodelets with roslaunch?
> >
> > The example in the tutorial seems to have no interdependencies or timing
> issues.
> >
> >
> http://www.ros.org/wiki/nodelet/Tutorials/Running%20a%20nodelet#Using_withing_roslaunch_files
> >
> > But, when I try to launch my driver nodelet along with a point cloud
> > nodelet that converts the raw scan data into ROS
> > sensor_msgs/PointCloud format, I seem to get startup sequencing
> > problems depending on the order in which things initialize. Sometimes
> > it works and sometimes no point cloud gets published. Here is a simple
> > example:
> >
> > <launch>
> >  <node pkg="nodelet" type="nodelet" name="velodyne_nodelet_manager"
> >        args="manager" />
> >  <node pkg="nodelet" type="nodelet" name="driver_nodelet"
> >        args="load velodyne_common/DriverNodelet velodyne_nodelet_manager"
> />
> >  <node pkg="nodelet" type="nodelet" name="pointcloud_nodelet"
> >        args="load velodyne_common/PointCloudNodelet
> > velodyne_nodelet_manager" />
> > </launch>
> >
> > I guess a "nodelet load" command sometimes arrives before the "nodelet
> > manager" is ready. Since roslaunch makes no guarantees about order, I
> > wonder how to solve it. I see no similar problems when dealing with
> > the node-based versions of these programs.
>
> No prioritised sequencing in roslaunch causes me a headache too,
> though I've never had a situation when the nodelet manager didn't
> launch before all my nodelets (I guess because its first in line in my
> launcher).
>
> 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.


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



-- 
Tully Foote
Systems Engineer
Willow Garage, Inc.
tfoote at willowgarage.com
(650) 475-2827
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20101109/6385468d/attachment-0003.html>


More information about the ros-users mailing list