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 "jsk_topic_tools/snapshot_nodelet.h"
00037
00038 namespace jsk_topic_tools
00039 {
00040 void Snapshot::onInit()
00041 {
00042 advertised_ = false;
00043 subscribing_ = false;
00044 pnh_ = getPrivateNodeHandle();
00045 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00046 "input", 1,
00047 &Snapshot::inputCallback, this);
00048 request_service_ = pnh_.advertiseService(
00049 "request",
00050 &Snapshot::requestCallback, this);
00051 }
00052
00053 void Snapshot::inputCallback(
00054 const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00055 {
00056 boost::mutex::scoped_lock lock(mutex_);
00057 if (!advertised_) {
00058 ros::AdvertiseOptions opts("output", 1,
00059 msg->getMD5Sum(),
00060 msg->getDataType(),
00061 msg->getMessageDefinition());
00062 opts.latch = false;
00063 pub_ = pnh_.advertise(opts);
00064 advertised_ = true;
00065 sub_.shutdown();
00066 }
00067 else {
00068 if (requested_) {
00069 pub_.publish(msg);
00070 requested_ = false;
00071 sub_.shutdown();
00072 }
00073 }
00074 }
00075
00076
00077 bool Snapshot::requestCallback(
00078 std_srvs::Empty::Request& req,
00079 std_srvs::Empty::Response& res)
00080 {
00081 boost::mutex::scoped_lock lock(mutex_);
00082 requested_ = true;
00083 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00084 "input", 1,
00085 &Snapshot::inputCallback, this);
00086 }
00087
00088 }
00089
00090 #include <pluginlib/class_list_macros.h>
00091 PLUGINLIB_EXPORT_CLASS (jsk_topic_tools::Snapshot, nodelet::Nodelet);