[ros-users] Nodelets

Nicholas Butko nbutko at ucsd.edu
Sun Dec 5 16:44:51 UTC 2010


Thanks Tully. This is helpful. 

So the suggestion, as I understand it, is to have a "camera nodelet manager" that (a) has a nodelet::Loader and (b) has a while (ros::ok()) {} loop. 

Something like 

{{{
	ros::init(argc, argv, "CameraImageServer");
	ros::NodeHandle n;
	nodelet::Loader l; //This is what we need to be a nodelet manager
	
	image_transport::ImageTransport it(n);
	sensor_msgs::CvBridge bridge;
	image_transport::Publisher image_pub;

	image_pub = it.advertise("image_topic",1);
	
	cv::VideoCapture cap(0); 

	ros::Rate loop_rate(100); 
	
	cv::Mat frame; 
	while (ros::ok()) {		
		cap >> frame; 
		try
		{			
			IplImage iplim = frame; 
			image_pub.publish(bridge.cvToImgMsg(&iplim, "bgr8"));
		}
		catch (sensor_msgs::CvBridgeException error)
		{
			ROS_ERROR("error");
		}
		ros::spinOnce();
		loop_rate.sleep(); 
	}
	
	return 0;
}
}}}

Then, assuming these nodes are in a "vision_nodelets" stack,  one would start this as a regular node, e.g. 
{{{
rosrun vision_nodelets CameraImageServer
}}}

 and then load nodes to that manager, e.g.

{{{
rosrun nodelet nodelet load vision_nodelets/FaceFinder nodelet_manager __name:=CameraImageServer
}}}

Is that about right?

--Nick
On Dec 5, 2010, at 12:31 AM, Tully Foote wrote:

> Hi Nick, 
> Replies below.
> 
> On Sat, Dec 4, 2010 at 3:24 PM, Nicholas Butko <nbutko at ucsd.edu> wrote:
> 
> On Dec 3, 2010, at 6:36 PM, Radu Bogdan Rusu wrote:
> 
> >
> > On 12/02/2010 01:54 PM, Patrick Bouffard wrote:
> >> Cool. One way to go would be a tutorial on how to transform a node
> >> into a nodelet. It seems to be a fairly simple recipe, modulo the
> >> blocking and threading stuff:
> >> - add the necessary #includes
> >> - get rid of int main()
> >> - subclass nodelet::Nodelet
> >> - move code from constructor to onInit()
> >> - add the PLUGINLIB_DECLARE_CLASS macro
> >> - add the<nodelet>  item in the<export>  part of the package manifest
> >> - create the .xml file to define the nodelet as a plugin
> >> - make the necessary changes to CMakeLists.txt (comment out a
> >> rosbuild_add_executable, add a rosbuild_add_library)
> >
> > Great, I added this as a starting point to http://www.ros.org/wiki/nodelet/Tutorials/Porting%20nodes%20to%20nodelets .
> > Can we all please fill in the page when we get a chance with more content?
> 
> Is there a nodelet equivalent of a "while (ros::ok()) {}" loop?
> 
> Nodelet's do not have a main thread, and currently do not have a voluntary shutdown method.  They will run until destructed on unload.  This is ticketed for an enhancement https://code.ros.org/trac/ros-pkg/ticket/4431
>  
> 
> I am trying to move some computer vision code to nodelets. The idea is to have one camera nodelet serving frames, and everybody else grabbing and processing them.
> 
> That is one of the goals of the nodelet design.  You can see my other ros-users post about how to add an nodelet::Loader class to your node and then you can just load into that manager.  http://code.ros.org/lurker/message/20101205.074703.0991b0ae.en.html
>  
> 
> From the "nodelet" examples, it looks like all work is typically done in onInit() and in subscriber callbacks.
> 
> onInit is not supposed to block and will cause problems if it does.   
> 
> So, to implement a camera server, I'd either have to never finish initializing (is this okay?) or to set up an extra node that sends "wakeup" messages every 30 ms or so, and grab frames in the callback.
> 
> Is there a way to set up a "callMeEvery30MS" callback function in a nodelet? Or even a "callAndLetMeRunForeverWhileOtherThreadsDoTheirThing()" callback function that could then run an infinite loop?
> 
> If you want periodic operations.  The ros::Timer object will give you periodic callbacks.  http://www.ros.org/doc/api/roscpp/html/classros_1_1Timer.html
> 
> Tully
> 
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users

-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20101205/c3f203bf/attachment-0003.html>


More information about the ros-users mailing list