@@ -319,6 +319,10 @@ class SpinnakerCameraNodelet : public nodelet::Nodelet
319319
320320 srv_->setCallback (f);
321321
322+ // queue size of ros publisher
323+ int queue_size;
324+ pnh.param <int >(" queue_size" , queue_size, 5 );
325+
322326 // Start the camera info manager and attempt to load any configurations
323327 std::stringstream cinfo_name;
324328 cinfo_name << serial;
@@ -327,7 +331,7 @@ class SpinnakerCameraNodelet : public nodelet::Nodelet
327331 // Publish topics using ImageTransport through camera_info_manager (gives cool things like compression)
328332 it_.reset (new image_transport::ImageTransport (nh));
329333 image_transport::SubscriberStatusCallback cb = boost::bind (&SpinnakerCameraNodelet::connectCb, this );
330- it_pub_ = it_->advertiseCamera (" image_raw" , 5 , cb, cb);
334+ it_pub_ = it_->advertiseCamera (" image_raw" , queue_size , cb, cb);
331335
332336 // Set up diagnostics
333337 updater_.setHardwareID (" spinnaker_camera " + cinfo_name.str ());
@@ -350,7 +354,7 @@ class SpinnakerCameraNodelet : public nodelet::Nodelet
350354 ros::SubscriberStatusCallback cb2 = boost::bind (&SpinnakerCameraNodelet::connectCb, this );
351355 pub_.reset (
352356 new diagnostic_updater::DiagnosedPublisher<wfov_camera_msgs::WFOVImage>(
353- nh.advertise <wfov_camera_msgs::WFOVImage>(" image" , 5 , cb2, cb2),
357+ nh.advertise <wfov_camera_msgs::WFOVImage>(" image" , queue_size , cb2, cb2),
354358 updater_, diagnostic_updater::FrequencyStatusParam (
355359 &min_freq_, &max_freq_, freq_tolerance, window_size),
356360 diagnostic_updater::TimeStampStatusParam (min_acceptable,
0 commit comments