// Handles (un)subscribing when clients (un)subscribe void PointCloud2Nodelet::connectCb() { boost::lock_guard<boost::mutex> lock(connect_mutex_); if (pub_points2_.getNumSubscribers() == 0) { sub_l_image_ .unsubscribe(); sub_l_info_ .unsubscribe(); sub_r_info_ .unsubscribe(); sub_disparity_.unsubscribe(); } else if (!sub_l_image_.getSubscriber()) { ros::NodeHandle &nh = getNodeHandle(); // Queue size 1 should be OK; the one that matters is the synchronizer queue size. sub_l_image_ .subscribe(*it_, "left/image_rect_color", 1); sub_l_info_ .subscribe(nh, "left/camera_info", 1); sub_r_info_ .subscribe(nh, "right/camera_info", 1); sub_disparity_.subscribe(nh, "disparity", 1); } }
// Handles (un)subscribing when clients (un)subscribe void DisparityWideNodelet::connectCb() { boost::lock_guard<boost::mutex> lock(connect_mutex_); if (pub_disparity_.getNumSubscribers() == 0) { sub_l_image_.unsubscribe(); sub_l_info_ .unsubscribe(); sub_r_image_.unsubscribe(); sub_r_info_ .unsubscribe(); } else if (!sub_l_image_.getSubscriber()) { ros::NodeHandle &nh = getNodeHandle(); // Queue size 1 should be OK; the one that matters is the synchronizer queue size. /// @todo Allow remapping left, right? image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle()); sub_l_image_.subscribe(*it_, "left_wide/image_rect", 1, hints); sub_l_info_ .subscribe(nh, "left_wide/camera_info", 1); sub_r_image_.subscribe(*it_, "right/image_rect", 1, hints); sub_r_info_ .subscribe(nh, "right/camera_info", 1); } }