Thanks Tully, I'd already suggested to him about writing a manager to handle pluginlibs designed with a specific interface in mind. I'm quite happy with that - it bundles the performance issues (related to mutexes and blocking) into as small and controlled a unit as possible and I also appreciate the consistency argument. Last thing we want is to affect, or have to delve into some relatively unknown bit of code in a package across the puddle to work out performance problems due to blocking. On 24 October 2010 17:54, Tully Foote wrote: > Hi Daniel, > > In the image pipeline every new image is allocated once and passed on. To > mutate it at an intermediate step it must be copied and mutated (these can > be combined often). If you add the locks as suggested and wait for the > subscriber to finish using the message, single subscriber doing a long > running operation can stop a source from publishing completely by holding > onto the lock for the message. Thereby blocking sending to all potential > subscribers indefinitely. > > The roscpp direct memory transports have restrictions. All callbacks which > don't automatically provide an dedicated copy use a const pointers so you > cannot mutate the data received. And the publisher has a responsibility to > not mutate the data structure after publish when publishing using a shared > pointer. > http://www.ros.org/doc/api/roscpp/html/classros_1_1Publisher.html#a16b7602d82ef89dff56a92cc7dc3d7cd > > These restrictions are in place to allow the anonymous publish subscribe > abstraction to remain consistent across all implementations. In anonymous > publish subscribe you do not know what else is listening or sending on any > topic. For example if you happen to run "rostopic echo /my_topic" or > "rostopic pub /my_topic 123" all of a sudden any reliance on the pointer or > a mutex being consistent is broken, for if it comes in over the wire the > receivers will get different copies. Also if a different nodelet is spun up > to debug the incoming topic and it stores the incoming messages to generate > an aggregate output, its output will be corrupted by changing the content of > the received message in a different nodelet. And as above if this nodelet > locked the message you lock the upstream publisher and no more messages > arrive. > > Taking away these restrictions you can do whatever you want, but you are no > longer an anonymous publish subscribe ROS transport. And ROS debugging and > introspection tools cannot work in all cases. > > If these restrictions are too restrictive sharing memory can be done many > ways, more generally than the roscpp transport. If you want to make the > parts dynamically loadable, I would suggest that you at pluginlib, where you > can build your arbitrary memory sharing ability into the baseclass for your > plugin. However in doing a custom system you will lose the general ROS > connectivity, debugging, and introspection. > > Tully > > > On Sat, Oct 23, 2010 at 6:32 PM, Daniel Stonier wrote: > >> >> >> On 24 October 2010 08:15, Josh Faust wrote: >> >>> A couple of the guys here at work were talking about passing around large >>>> objects with the nodelets when we realised there was no thread safety >>>> attached to the objects that were getting passed around. Is there any plans >>>> to add this functionality to them? i.e. either via something like a >>>> Mutex.msg you could include with your other msg's (aka Time.msg) or perhaps >>>> via a thread safe shared pointer that you could use when publishing. >>>> >>> >>> I'm not really sure what you mean -- boost::shared_ptr is atomically >>> reference counted, so it the object won't be deleted out from under you if >>> you have multiple subscribers to the same topic. If you need to modify the >>> object in the subscriber you can subscribe to a non-const version of the >>> message, and it will make a copy for you if there are multiple subscribers. >>> Do you mean you want to be able to modify the object on the publisher side >>> after you've sent it? >>> >>> Josh >>> >> >> Yes, exactly. i.e. sharing a large object between publisher and >> subscriber(s) and you want to avoid any copying or recreation of the object. >> The publisher is continually updating the large object and the subscribers >> don't want to get caught by an update in the middle of reading. Is there >> perhaps a better approach to this? How do the guys in the image pipeline >> handle the sending of big objects - they simply recreate a new object every >> time they want to send one? >> >> >>> >>> _______________________________________________ >>> ros-users mailing list >>> ros-users@code.ros.org >>> https://code.ros.org/mailman/listinfo/ros-users >>> >>> >> >> >> -- >> Phone : +82-10-5400-3296 (010-5400-3296) >> Home: http://snorriheim.dnsdojo.com/ >> Yujin Robot: http://www.yujinrobot.com/ >> Embedded Ros : http://www.ros.org/wiki/eros >> Embedded Control Libraries: >> http://snorriheim.dnsdojo.com/redmine/wiki/ecl >> >> _______________________________________________ >> ros-users mailing list >> ros-users@code.ros.org >> https://code.ros.org/mailman/listinfo/ros-users >> >> > > > -- > Tully Foote > Systems Engineer > Willow Garage, Inc. > tfoote@willowgarage.com > (650) 475-2827 > > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > > -- Phone : +82-10-5400-3296 (010-5400-3296) Home: http://snorriheim.dnsdojo.com/ Yujin Robot: http://www.yujinrobot.com/ Embedded Control Libraries: http://snorriheim.dnsdojo.com/redmine/wiki/ecl