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 #include <pluginlib/class_list_macros.h>
00035 #include "jsk_topic_tools/relay_nodelet.h"
00036
00037 namespace jsk_topic_tools
00038 {
00039
00040 void Relay::onInit()
00041 {
00042 output_topic_name_ = "output";
00043 connection_status_ = NOT_INITIALIZED;
00044 pnh_ = getPrivateNodeHandle();
00045
00046 diagnostic_updater_.reset(
00047 new TimeredDiagnosticUpdater(pnh_, ros::Duration(1.0)));
00048 diagnostic_updater_->setHardwareID(getName());
00049 diagnostic_updater_->add(
00050 getName() + "::Relay",
00051 boost::bind(
00052 &Relay::updateDiagnostic, this, _1));
00053 double vital_rate;
00054 pnh_.param("vital_rate", vital_rate, 1.0);
00055 vital_checker_.reset(
00056 new jsk_topic_tools::VitalChecker(1 / vital_rate));
00057 diagnostic_updater_->start();
00058 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00059 "input", 1,
00060 &Relay::inputCallback, this);
00061 change_output_topic_srv_ = pnh_.advertiseService(
00062 "change_output_topic", &Relay::changeOutputTopicCallback, this);
00063 }
00064
00065 void Relay::updateDiagnostic(
00066 diagnostic_updater::DiagnosticStatusWrapper &stat)
00067 {
00068 boost::mutex::scoped_lock lock(mutex_);
00069 if (connection_status_ == NOT_INITIALIZED) {
00070 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00071 "not initialized. Is "
00072 + pnh_.resolveName("input") + " active?");
00073 }
00074 else if (connection_status_ == SUBSCRIBED) {
00075 if (vital_checker_->isAlive()) {
00076 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00077 "subscribed: " + pnh_.resolveName("output"));
00078 }
00079 else {
00080 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00081 "subscribed but no input. Is "
00082 + pnh_.resolveName("input") + " active?");
00083 }
00084 vital_checker_->registerStatInfo(stat);
00085 }
00086 else if (connection_status_ == NOT_SUBSCRIBED) {
00087 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00088 "not subscribed: " + pnh_.resolveName("output"));
00089 }
00090 stat.add("input topic", pnh_.resolveName("input"));
00091 stat.add("output topic", pnh_.resolveName("output"));
00092 }
00093
00094 void Relay::inputCallback(const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00095 {
00096 boost::mutex::scoped_lock lock(mutex_);
00097 if (connection_status_ == NOT_INITIALIZED) {
00098
00099
00100
00101
00102 pub_ = advertise(msg, output_topic_name_);
00103 connection_status_ = NOT_SUBSCRIBED;
00104
00105 sub_.shutdown();
00106 sample_msg_ = msg;
00107 }
00108 else if (pub_.getNumSubscribers() > 0) {
00109 vital_checker_->poke();
00110 pub_.publish(msg);
00111 }
00112 }
00113
00114 void Relay::connectCb()
00115 {
00116 boost::mutex::scoped_lock lock(mutex_);
00117 NODELET_DEBUG("connectCB");
00118 if (connection_status_ != NOT_INITIALIZED) {
00119 if (pub_.getNumSubscribers() > 0) {
00120 if (connection_status_ == NOT_SUBSCRIBED) {
00121 NODELET_DEBUG("suscribe");
00122 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>("input", 1,
00123 &Relay::inputCallback, this);
00124 connection_status_ = SUBSCRIBED;
00125 }
00126 }
00127 }
00128 }
00129
00130 void Relay::disconnectCb()
00131 {
00132 boost::mutex::scoped_lock lock(mutex_);
00133 NODELET_DEBUG("disconnectCb");
00134 if (connection_status_ != NOT_INITIALIZED) {
00135 if (pub_.getNumSubscribers() == 0) {
00136 if (connection_status_ == SUBSCRIBED) {
00137 NODELET_DEBUG("disconnect");
00138 sub_.shutdown();
00139 connection_status_ = NOT_SUBSCRIBED;
00140 }
00141 }
00142 }
00143 }
00144
00145 ros::Publisher Relay::advertise(
00146 boost::shared_ptr<topic_tools::ShapeShifter const> msg,
00147 const std::string& topic)
00148 {
00149 ros::SubscriberStatusCallback connect_cb
00150 = boost::bind( &Relay::connectCb, this);
00151 ros::SubscriberStatusCallback disconnect_cb
00152 = boost::bind( &Relay::disconnectCb, this);
00153 ros::AdvertiseOptions opts(topic, 1,
00154 msg->getMD5Sum(),
00155 msg->getDataType(),
00156 msg->getMessageDefinition(),
00157 connect_cb,
00158 disconnect_cb);
00159 opts.latch = false;
00160 return pnh_.advertise(opts);
00161 }
00162
00163 bool Relay::changeOutputTopicCallback(
00164 jsk_topic_tools::ChangeTopic::Request &req,
00165 jsk_topic_tools::ChangeTopic::Response &res)
00166 {
00167 boost::mutex::scoped_lock lock(mutex_);
00168 output_topic_name_ = req.topic;
00169 if (sample_msg_) {
00170 pub_ = advertise(sample_msg_, output_topic_name_);
00171 }
00172 return true;
00173 }
00174 }
00175
00176 typedef jsk_topic_tools::Relay Relay;
00177 PLUGINLIB_EXPORT_CLASS(Relay, nodelet::Nodelet)