36 #include <std_msgs/String.h> 50 NODELET_FATAL(
"need to specify at least one topic in ~topics");
94 topic_tools::MuxSelect::Response &res)
102 if (req.topic == g_none_topic) {
106 for (
size_t i = 0; i <
topics_.size(); i++) {
115 NODELET_WARN(
"%s is not provided in topic list", req.topic.c_str());
120 topic_tools::MuxAdd::Response& res)
122 NODELET_INFO(
"trying to add %s to mux", req.topic.c_str());
123 if (req.topic == g_none_topic) {
124 NODELET_WARN(
"failed to add topic %s to mux, because it's reserved for special use",
129 for (
size_t i = 0; i <
topics_.size(); i++) {
131 NODELET_WARN(
"tried to add a topic that mux was already listening to: [%s]",
145 topic_tools::MuxDelete::Response& res)
148 for (
size_t i = 0; i <
topics_.size(); i++) {
151 NODELET_WARN(
"tried to delete currently selected topic %s from mux",
159 NODELET_WARN(
"cannot find the topics %s in the list of mux",
165 topic_tools::MuxList::Response& res)
167 for (
size_t i = 0; i <
topics_.size(); i++) {
188 std_msgs::String
msg;
201 msg->getMessageDefinition(),
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
PLUGINLIB_EXPORT_CLASS(jsk_topic_tools::Snapshot, nodelet::Nodelet)
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::NodeHandle & getPrivateNodeHandle() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
#define NODELET_FATAL(...)