[ros-users] Nodelets

Tully Foote tfoote at willowgarage.com
Thu Dec 2 18:45:29 UTC 2010


Hi Pat,

On Thu, Dec 2, 2010 at 9:32 AM, Patrick Bouffard <bouffard at eecs.berkeley.edu
> wrote:

> Hi Tully,
>
> On Wed, Dec 1, 2010 at 4:44 PM, Tully Foote <tfoote at willowgarage.com>
> wrote:
> > Hi Patrick,
> >
> > onInit() is required to return.  See
> >
> http://ros-users.122217.n3.nabble.com/questions-about-nodelets-td1869563.html#a1871466
> > for past discussions.
>
> Yes, I saw that thread.
>
> > It is true that if you want to block n threads you need to have more than
> n
> > threads available.  We have not set any rules as to what you can set the
> > number of threads, but the rule of >1 thread per worker is not
> necessarily
> > what you want if you are trying to optimize # threads vs # cpu cores, if
> you
> > thrash 10 threads across 2 cores you can significantly decrease
> > performance.
>
> But how would it compare to having 10 processes instead of 10 threads,
> and the extra overhead of using the TCP/IP stack to communicate
> between them? If the performance with nodelets isn't improved over the
> separate processes option then I guess I don't see why one would go
> with nodelets at all.
>

In terms of pure computation nodelets do not change anything.  However
nodelets allow zero copy transport of data between components.  Depending on
what type of data and the speed at which you are processing data the
overhead of TCP/IP stack becomes prohibitively expensive, which is what
nodelets are designed to help with.  The places where this starts to become
noticable are when you start streaming video or full camera frame point
clouds at 30 Hz.


> > We thought about having separate thread pools for each nodelet
> > inside the manager but that too starts to get unreasonably complicated,
> and
> > adds overhead, plus potentially running out of threads. There ends up not
> > being any solution which is completely general and addresses all use
> cases.
>
> That's fair, but I suspect that the use case that I describe is one of
> the more common ones, and if I'm interpreting what I've seen on the
> lists correctly, isn't that the direction that ROS is going in general
> anyway (i.e. where the 'default' building block is a nodelet rather
> than a node). At any rate it would be good to see a more extensive
> example/tutorial for nodelets, that at least addresses the threading
> issue. It may not cover all the use cases but it would still be an
> improvement IMHO.
>

Indeed we do need to improve documentation.  I've opened a ticket to remind
myself https://code.ros.org/trac/ros-pkg/ticket/4602    In general for high
throughput environments nodelets are likely going to start to dominate due
to the higher transport efficiency.  But the simplicity of having a separate
process will mean that for low bandwidth things standalone nodes will likely
persist.


> > Our decision was that if you're using the multithreaded interface you
> know
> > that you have to think about the number of threads available.
>
> The nodelet design does seem to encourage on-the-fly nodelet loading
> and unloading; in my case I might want to take advantage of that as
> well. Is there a mechanism to change the number of worker threads as
> nodelets are loaded/unloaded?
>

There's not a mechanism to do so  I've ticketed it at
https://code.ros.org/trac/ros-pkg/ticket/4603


Thanks for the feedback,
Tully


>
> > The NODELET_(INFO/DEBUG/...) setup a named logger such that you can
> > differentiate between the output of two of the same type nodelets running
> on
> > the same manager.  It also has the advantage that you can turn one
> specific
> > nodelet into debug, instead of all nodelets of a specific type.
>
> Ok, so then it sounds like one should always use these in nodelets,
> though there's no harm in ROS_(INFO/DEBUG/...) either. Thanks.
>
> Cheers,
> Pat
>
>
> > Tully
> >
> > On Wed, Dec 1, 2010 at 3:28 PM, Patrick Bouffard
> > <bouffard at eecs.berkeley.edu> wrote:
> >>
> >> After a bit of hacking around I think I found a solution, at least for
> >> now. Instead of doing the waitForService and service call in the
> >> onInit method of my nodelets (where it can block), I set up a one-shot
> >> timer which invokes a method that does the same thing. It also seems
> >> that upping the num_worker_threads parameter of the nodelet manager
> >> was required as well. In my case things start working as expected when
> >> I set it to 5 or higher (reliably, anyway--at lower numbers it might
> >> sometimes work, and I think that has to do with the unpredictable
> >> order of startup--if the 'client' nodelets grab all the threads first,
> >> then the 'server' nodelet is waiting forever for a thread on which to
> >> advertise its service). I'm loading a total of 6 nodelets for the time
> >> being but only 5 of them would be involved in the startup blocking
> >> problem, so I think this makes sense.
> >>
> >> Would it then be a good rule of thumb to set num_worker_threads to at
> >> least the number of nodelets being loaded into a manager? Is there a
> >> large performance penalty for having too many worker threads?
> >>
> >> Pat
> >>
> >> On Wed, Dec 1, 2010 at 12:54 PM, Patrick Bouffard
> >> <bouffard at eecs.berkeley.edu> wrote:
> >> > I'm trying to consolidate a number of separate nodes into a single
> >> > process using nodelets. I think I worked out the changes necessary to
> >> > go from ordinary nodes to nodelets that can be run standalone. But
> >> > when I try to take those same nodelets and load them all into a
> >> > nodelet manager, things start to break. I think this might have
> >> > something to do with threading/callback queues or something to that
> >> > effect.
> >> >
> >> > One of the things that my node(let)s do at startup is to wait for a
> >> > service to be advertised. The node that advertises that service is now
> >> > one of the nodelets, and I notice that when I load the nodelets that
> >> > are the service clients into the nodelet manager, the service doesn't
> >> > ever seem to start. I suspect this might be because when I call
> >> > ros::service::waitForService(), it's blocking all of the nodelets,
> >> > including the one that would be advertising the service--does that
> >> > make sense? What is the Right Thing to do here to get the illusion of
> >> > having multiple nodes but with them running in the same process to
> >> > take advantage of zero-copy message passing etc.?
> >> >
> >> > Initially I thought perhaps I just need to add ros::spin() in the
> >> > onInit method in each nodelet, but I saw in another thread (no pun
> >> > intended :-) that this is not correct. I'm guessing the answer lies in
> >> > threading but I'm not quite sure where to start. Is there anywhere in
> >> > the ROS ecosystem a package that has a similar structure to what I'm
> >> > trying to do, that I could look at as an example?
> >> >
> >> > Also, I'm wondering what the distinction between ROS_INFO and
> >> > NODELET_INFO is; should I always be using the latter in nodelets?
> >> >
> >> > Thanks,
> >> > Pat
> >> >
> >> _______________________________________________
> >> 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
> >
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org
> > https://code.ros.org/mailman/listinfo/ros-users
> >
> >
> _______________________________________________
> 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/20101202/3b161a49/attachment-0003.html>


More information about the ros-users mailing list