publication.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_PUBLICATION_H
29 #define ROSCPP_PUBLICATION_H
30 
31 #include "ros/forwards.h"
32 #include "ros/advertise_options.h"
33 #include "common.h"
34 #include "xmlrpcpp/XmlRpc.h"
35 
36 #include <boost/thread/mutex.hpp>
37 
38 #include <boost/shared_ptr.hpp>
39 #include <boost/shared_array.hpp>
40 
41 #include <vector>
42 
43 namespace ros
44 {
45 
46 class SubscriberLink;
48 typedef std::vector<SubscriberLinkPtr> V_SubscriberLink;
49 
53 class ROSCPP_DECL Publication
54 {
55 public:
56  Publication(const std::string &name,
57  const std::string& datatype,
58  const std::string& _md5sum,
59  const std::string& message_definition,
60  size_t max_queue,
61  bool /* unused */,
62  bool has_header);
63 
64  ~Publication();
65 
66  void addCallbacks(const SubscriberCallbacksPtr& callbacks);
67  void removeCallbacks(const SubscriberCallbacksPtr& callbacks);
68 
72  bool enqueueMessage(const SerializedMessage& m);
76  inline size_t getMaxQueue() { return max_queue_; }
80  XmlRpc::XmlRpcValue getStats();
84  void getInfo(XmlRpc::XmlRpcValue& info);
85 
89  bool hasSubscribers();
93  uint32_t getNumSubscribers();
94 
95  void getPublishTypes(bool& serialize, bool& nocopy, const std::type_info& ti);
96 
100  const std::string& getName() const { return name_; }
104  const std::string& getDataType() const { return datatype_; }
108  const std::string& getMD5Sum() const { return md5sum_; }
112  const std::string& getMessageDefinition() const { return message_definition_; }
116  uint32_t getSequence() { return seq_; }
117 
118  bool isLatched();
119 
123  void addSubscriberLink(const SubscriberLinkPtr& sub_link);
127  void removeSubscriberLink(const SubscriberLinkPtr& sub_link);
128 
132  void drop();
136  bool isDropped() { return dropped_; }
137 
138  uint32_t incrementSequence();
139 
140  size_t getNumCallbacks();
141 
142  bool isLatching() { return isLatched(); }
143 
144  void publish(SerializedMessage& m);
145  void processPublishQueue();
146 
147  bool validateHeader(const Header& h, std::string& error_msg);
148 
149 private:
150  void dropAllConnections();
151 
155  void peerConnect(const SubscriberLinkPtr& sub_link);
159  void peerDisconnect(const SubscriberLinkPtr& sub_link);
160 
161  std::string name_;
162  std::string datatype_;
163  std::string md5sum_;
164  std::string message_definition_;
165  size_t max_queue_;
166  uint32_t seq_;
167  boost::mutex seq_mutex_;
168 
169  typedef std::vector<SubscriberCallbacksPtr> V_Callback;
171  boost::mutex callbacks_mutex_;
172 
174  // We use a recursive mutex here for the rare case that a publish call causes another one (like in the case of a rosconsole call)
176 
177  bool dropped_;
178 
179  bool latch_;
181 
183 
184  typedef std::vector<SerializedMessage> V_SerializedMessage;
186  boost::mutex publish_queue_mutex_;
187 };
188 
189 }
190 
191 #endif // ROSCPP_PUBLICATION_H
ros::Publication::dropped_
bool dropped_
Definition: publication.h:177
ros::SerializedMessage
ros::Publication::V_SerializedMessage
std::vector< SerializedMessage > V_SerializedMessage
Definition: publication.h:184
ros::Publication::isDropped
bool isDropped()
Returns if this publication is valid or not.
Definition: publication.h:136
ros::SubscriberLinkPtr
boost::shared_ptr< SubscriberLink > SubscriberLinkPtr
Definition: forwards.h:69
ros::Publication::getName
const std::string & getName() const
Returns the name of the topic this publication broadcasts to.
Definition: publication.h:100
ros::Publication::subscriber_links_mutex_
boost::mutex subscriber_links_mutex_
Definition: publication.h:175
boost::shared_ptr< SubscriberLink >
ros::Publication::callbacks_
V_Callback callbacks_
Definition: publication.h:170
forwards.h
ros::V_SubscriberLink
std::vector< SubscriberLinkPtr > V_SubscriberLink
Definition: forwards.h:71
ros
ros::Publication::callbacks_mutex_
boost::mutex callbacks_mutex_
Definition: publication.h:171
ros::Header
ros::Publication::getMD5Sum
const std::string & getMD5Sum() const
Returns the md5sum of the message published by this publication.
Definition: publication.h:108
ros::Publication::publish_queue_
V_SerializedMessage publish_queue_
Definition: publication.h:185
ros::Publication::publish_queue_mutex_
boost::mutex publish_queue_mutex_
Definition: publication.h:186
advertise_options.h
ros::Publication::md5sum_
std::string md5sum_
Definition: publication.h:163
ros::Publication::latch_
bool latch_
Definition: publication.h:179
ros::Publication::seq_mutex_
boost::mutex seq_mutex_
Definition: publication.h:167
ros::Publication::message_definition_
std::string message_definition_
Definition: publication.h:164
XmlRpc.h
ros::Publication
A Publication manages an advertised topic.
Definition: publication.h:53
ros::Publication::V_Callback
std::vector< SubscriberCallbacksPtr > V_Callback
Definition: publication.h:169
ros::Publication::getMessageDefinition
const std::string & getMessageDefinition() const
Returns the full definition of the message published by this publication.
Definition: publication.h:112
ros::Publication::isLatching
bool isLatching()
Definition: publication.h:142
ros::Publication::intraprocess_subscriber_count_
uint32_t intraprocess_subscriber_count_
Definition: publication.h:182
ros::Publication::getSequence
uint32_t getSequence()
Returns the sequence number.
Definition: publication.h:116
ros::Publication::has_header_
bool has_header_
Definition: publication.h:180
datatype
const char * datatype()
ros::Publication::subscriber_links_
V_SubscriberLink subscriber_links_
Definition: publication.h:173
ros::Publication::name_
std::string name_
Definition: publication.h:161
ros::Publication::getMaxQueue
size_t getMaxQueue()
returns the max queue size of this publication
Definition: publication.h:76
ros::Publication::datatype_
std::string datatype_
Definition: publication.h:162
XmlRpc::XmlRpcValue
ros::Publication::seq_
uint32_t seq_
Definition: publication.h:166
ros::Publication::getDataType
const std::string & getDataType() const
Returns the data type of the message published by this publication.
Definition: publication.h:104
ros::Publication::max_queue_
size_t max_queue_
Definition: publication.h:165


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:35