17 #include <unordered_map> 22 std::vector<std::string> listTopics(
const std::string &type_name);
23 std::vector<std::string> listTopics();
25 static const std::shared_ptr<TopicManager> &instance();
31 std::string _topic_name;
32 ros::Subscriber _ros_subscriber;
33 std::mutex _message_mutex;
34 std::shared_ptr<const Message> _message_instance;
35 std::atomic<size_t> _connections;
36 std::shared_ptr<TopicRegistry> _registry;
37 Topic(
const std::string &name);
40 static void _subscribe(
const std::shared_ptr<Topic> &topic);
41 static void _unsubscribe(
const std::shared_ptr<Topic> &topic);
45 void countConnection(
size_t d) { _connections += d; }
46 void publish(
const std::shared_ptr<const Message> &message);
47 inline const std::string &name()
const {
return _topic_name; }
48 std::shared_ptr<const Message> message() {
49 std::unique_lock<std::mutex> lock(_message_mutex);
50 return _message_instance;
52 static std::shared_ptr<Topic> instance(
const std::string &name);
55 bool isFromBag()
const;
61 std::vector<std::string> _topics;
62 std::shared_ptr<TopicRegistry> _registry;
73 std::unique_ptr<ros::Publisher> _publisher;
77 Publisher(
const std::string &topic) { this->topic(topic); }
80 const std::string &topic()
const {
return _topic; }
81 void topic(
const std::string &topic) {
82 if (topic != _topic) {
87 static ros::NodeHandle ros_node;
89 new ros::Publisher(ros_node.advertise<
Message>(topic, 1000)));
94 bool connected()
const {
95 return _publisher && _publisher->getNumSubscribers() > 0;
97 void publish(
const Message &message) {
99 _publisher->publish(message);
102 void publish(
const std::shared_ptr<const Message> &message) {
104 _publisher->publish(*message);
107 void publish(
const std::string &topic,
const Message &message) {
110 _publisher->publish(message);
113 void publish(
const std::string &topic,
114 const std::shared_ptr<const Message> &message) {
117 _publisher->publish(*message);
124 std::weak_ptr<const void> receiver;
126 bool _visible =
true;
127 std::shared_ptr<Callback> _callback;
128 std::shared_ptr<Topic> _topic;
129 std::shared_ptr<const M> _message_instance;
133 std::shared_ptr<const Message> _message;
136 inline MessageCast(
const std::shared_ptr<const Message> &message)
137 : _message(message) {}
138 inline operator std::shared_ptr<const Message>() {
return _message; }
139 template <
class T>
inline operator std::shared_ptr<T>() {
140 return _message ? _message->instantiate<T>() :
nullptr;
144 static void invoke(
const F &callback,
145 const std::shared_ptr<const Message> &message) {
149 callback(MessageCast(message));
153 Subscriber(
const std::string &name,
bool visible =
true) {
154 _topic = Topic::instance(name);
157 _topic->countConnection(+1);
162 const std::shared_ptr<const void> &receiver,
const F &
function,
163 bool visible =
true) {
164 _topic = Topic::instance(name);
165 _callback = std::make_shared<Callback>();
166 _callback->receiver = receiver;
167 auto *callback_ptr = _callback.get();
168 _topic->received.connect(
169 _callback, [callback_ptr,
170 function](
const std::shared_ptr<const Message> &message) {
171 if (
auto ptr = callback_ptr->receiver.lock()) {
172 invoke(
function, message);
175 invoke(
function, _topic->message());
178 _topic->countConnection(+1);
183 _topic->countConnection(-1);
188 const std::shared_ptr<Topic> &topic()
const {
return _topic; }
189 std::shared_ptr<const M> message() {
190 auto msg = _topic->message();
191 if (_watcher.changed(msg)) {
193 _message_instance = msg->instantiate<M>();
195 _message_instance =
nullptr;
197 LOG_DEBUG(
"message instance " << msg.get() <<
" " 198 << _message_instance.get());
200 return _message_instance;
205 std::shared_ptr<void> _instance;
218 std::shared_ptr<void> _callback_object;
219 std::function<void(const std::shared_ptr<const Message> &)>
221 std::shared_ptr<Subscriber<Message>> _subscriber;
223 if ((_topic.empty() || !_used) && _subscriber) {
224 _subscriber =
nullptr;
226 if (!_topic.empty() && _used) {
227 if (!_subscriber || _subscriber->topic()->name() != _topic) {
228 if (_callback_object && _callback_function) {
229 _subscriber = std::make_shared<Subscriber<Message>>(
230 _topic, _callback_object, _callback_function);
232 _subscriber = std::make_shared<Subscriber<Message>>(_topic);
242 _topic = other._topic;
246 _topic = other._topic;
250 void connect(
const std::shared_ptr<void> &callback_object,
251 const std::function<
void(
const std::shared_ptr<const Message> &)>
252 &callback_function) {
254 _callback_object = callback_object;
255 _callback_function = callback_function;
262 const std::string &topic()
const {
return _topic; }
263 void topic(
const std::string &topic) {
264 if (topic != _topic) {
269 std::shared_ptr<const Message> message() {
273 return _subscriber->message();
277 std::shared_ptr<Subscriber<Message>> subscriber() {
293 return a.topic() == b.topic();
297 return a.topic() != b.topic();
301 attributes->list = [](
const Property &property) {
303 return TopicManager::instance()->listTopics(
304 ros::message_traits::DataType<T>::value());