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


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
 

Tully, I have been playing around with this approach, trying to get it to work. I have been having some trouble. The nodelets are loaded, onInit() is called, but callbacks aren't called on the nodelets. Is there something about ros::spinOnce() that doesn't do the right thing for nodelets?

Below is a detailed example, if it helps. 

--Nick 

===========

I set up something similar to this example, but that also  publishes a message:

{{{
int main(int argc, char** argv)
{
ros::init(argc, argv, "VisionNodeletManager");
ros::NodeHandle n;
nodelet::Loader l; //This is what we need to be a nodelet manager

ros::Publisher pub = n.advertise<std_msgs::Bool>("camera_display_disable", 1000);

ros::Rate loop_rate(1);

while (ros::ok()) {
std_msgs::Bool msg; 
msg.data = 0
pub.publish(msg); 
ROS_INFO_STREAM("Published frame."); 
ros::spinOnce();
loop_rate.sleep(); 
}


return 0;
}
}}}

I then set up a listener nodelet: 

{{{
namespace vision_nodelets
{


class CameraDisplayNodelet : public nodelet::Nodelet
{
public:
CameraDisplayNodelet() : 
disabled_(0), 
{}


private:
virtual void onInit()
{
ROS_INFO_STREAM("Calling onInit() for CameraDisplayNodelet"); 
ros::NodeHandle& private_nh = getPrivateNodeHandle();
private_nh.getParam("disabled", disabled_);
ROS_INFO_STREAM("Parameters: disabled=" << disabled_ ); 
sub = private_nh.subscribe("camera_display_disable", 1000, &CameraDisplayNodelet::callback, this);
ROS_INFO_STREAM("Finished onInit()"); 
}



void callback(const std_msgs::Bool::ConstPtr& input)
{
ROS_INFO_STREAM("Received message: camera_display_disable=" << input->data); 
disabled_ = input->data;
}
int disabled_; 
ros::Subscriber sub;


};


PLUGINLIB_DECLARE_CLASS(vision_nodelets, CameraDisplayNodelet, vision_nodelets::CameraDisplayNodelet, nodelet::Nodelet);
}

}}}

In Terminal A, I run 

{{{
rosrun vision_nodelets vision_nodelet_manager 
}}}

In Terminal B, I run 

{{{
rosrun nodelet nodelet load vision_nodelets/CameraDisplayNodelet VisionNodeletManager
}}}

In Terminal C, I run

{{{
rostopic echo /camera_display_disable
}}}

The following behavior is observed: 

In Terminal A I see unexpected outpt:
Every second I see the message "Published Frame". When the nodelet is started in Terminal B, I see "Calling onInit()"... I never see "Received message."

In Terminal B I see expected output:
{{{
[ INFO] [1291578492.136581000]: Loading nodelet /vision_nodelets_CameraDisplayNodelet of type vision_nodelets/CameraDisplayNodelet to manager VisionNodeletManager with the following remappings:
}}}

In Terminal C I see expected output: 
Once every second I see
{{{
---
data: False
}}}