Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "opencv_apps/nodelet.h"
00037
00038 namespace opencv_apps
00039 {
00040 void Nodelet::onInit()
00041 {
00042 connection_status_ = NOT_SUBSCRIBED;
00043 nh_.reset (new ros::NodeHandle (getMTNodeHandle ()));
00044 pnh_.reset (new ros::NodeHandle (getMTPrivateNodeHandle ()));
00045 pnh_->param("always_subscribe", always_subscribe_, false);
00046 pnh_->param("verbose_connection", verbose_connection_, false);
00047 if (!verbose_connection_) {
00048 nh_->param("verbose_connection", verbose_connection_, false);
00049 }
00050
00051 ever_subscribed_ = false;
00052 timer_ = nh_->createWallTimer(
00053 ros::WallDuration(5),
00054 &Nodelet::warnNeverSubscribedCallback,
00055 this,
00056 true);
00057 }
00058
00059 void Nodelet::onInitPostProcess()
00060 {
00061 if (always_subscribe_) {
00062 subscribe();
00063 }
00064 }
00065
00066 void Nodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent& event)
00067 {
00068 if (!ever_subscribed_) {
00069 NODELET_WARN("'%s' subscribes topics only with child subscribers.", nodelet::Nodelet::getName().c_str());
00070 }
00071 }
00072
00073 void Nodelet::connectionCallback(const ros::SingleSubscriberPublisher& pub)
00074 {
00075 if (verbose_connection_) {
00076 NODELET_INFO("New connection or disconnection is detected");
00077 }
00078 if (!always_subscribe_) {
00079 boost::mutex::scoped_lock lock(connection_mutex_);
00080 for (size_t i = 0; i < publishers_.size(); i++) {
00081 ros::Publisher pub = publishers_[i];
00082 if (pub.getNumSubscribers() > 0) {
00083 if (!ever_subscribed_) {
00084 ever_subscribed_ = true;
00085 }
00086 if (connection_status_ != SUBSCRIBED) {
00087 if (verbose_connection_) {
00088 NODELET_INFO("Subscribe input topics");
00089 }
00090 subscribe();
00091 connection_status_ = SUBSCRIBED;
00092 }
00093 return;
00094 }
00095 }
00096 if (connection_status_ == SUBSCRIBED) {
00097 if (verbose_connection_) {
00098 NODELET_INFO("Unsubscribe input topics");
00099 }
00100 unsubscribe();
00101 connection_status_ = NOT_SUBSCRIBED;
00102 }
00103 }
00104 }
00105
00106 void Nodelet::imageConnectionCallback(
00107 const image_transport::SingleSubscriberPublisher& pub)
00108 {
00109 if (verbose_connection_) {
00110 NODELET_INFO("New image connection or disconnection is detected");
00111 }
00112 if (!always_subscribe_) {
00113 boost::mutex::scoped_lock lock(connection_mutex_);
00114 for (size_t i = 0; i < image_publishers_.size(); i++) {
00115 image_transport::Publisher pub = image_publishers_[i];
00116 if (pub.getNumSubscribers() > 0) {
00117 if (!ever_subscribed_) {
00118 ever_subscribed_ = true;
00119 }
00120 if (connection_status_ != SUBSCRIBED) {
00121 if (verbose_connection_) {
00122 NODELET_INFO("Subscribe input topics");
00123 }
00124 subscribe();
00125 connection_status_ = SUBSCRIBED;
00126 }
00127 return;
00128 }
00129 }
00130 if (connection_status_ == SUBSCRIBED) {
00131 if (verbose_connection_) {
00132 NODELET_INFO("Unsubscribe input topics");
00133 }
00134 unsubscribe();
00135 connection_status_ = NOT_SUBSCRIBED;
00136 }
00137 }
00138 }
00139
00140 void Nodelet::cameraConnectionCallback(
00141 const image_transport::SingleSubscriberPublisher& pub)
00142 {
00143 cameraConnectionBaseCallback();
00144 }
00145
00146 void Nodelet::cameraInfoConnectionCallback(
00147 const ros::SingleSubscriberPublisher& pub)
00148 {
00149 cameraConnectionBaseCallback();
00150 }
00151
00152 void Nodelet::cameraConnectionBaseCallback()
00153 {
00154 if (verbose_connection_) {
00155 NODELET_INFO("New image connection or disconnection is detected");
00156 }
00157 if (!always_subscribe_) {
00158 boost::mutex::scoped_lock lock(connection_mutex_);
00159 for (size_t i = 0; i < camera_publishers_.size(); i++) {
00160 image_transport::CameraPublisher pub = camera_publishers_[i];
00161 if (pub.getNumSubscribers() > 0) {
00162 if (!ever_subscribed_) {
00163 ever_subscribed_ = true;
00164 }
00165 if (connection_status_ != SUBSCRIBED) {
00166 if (verbose_connection_) {
00167 NODELET_INFO("Subscribe input topics");
00168 }
00169 subscribe();
00170 connection_status_ = SUBSCRIBED;
00171 }
00172 return;
00173 }
00174 }
00175 if (connection_status_ == SUBSCRIBED) {
00176 if (verbose_connection_) {
00177 NODELET_INFO("Unsubscribe input topics");
00178 }
00179 unsubscribe();
00180 connection_status_ = NOT_SUBSCRIBED;
00181 }
00182 }
00183 }
00184 }