|
1 | | -#pragma once |
2 | | - |
3 | | -#include <iostream> |
4 | | -#include <string> |
5 | | -#include <thread> |
6 | | -#include <functional> |
7 | | -#include <unordered_map> |
8 | | -#include <list> |
9 | | -#include <queue> |
10 | | -#include <chrono> |
11 | | - |
12 | | -#include <stdio.h> |
13 | | -#include "types.h" |
14 | | -#include "helper.h" |
15 | | -#include "spinlock.h" |
16 | | - |
17 | | -#include "itransport_layer.h" |
18 | | - |
19 | | -#include "rapidjson/document.h" |
20 | | -#include "rapidjson/writer.h" |
21 | | -#include "rapidjson/stringbuffer.h" |
22 | | - |
23 | | -#include "messages/rosbridge_advertise_msg.h" |
24 | | -#include "messages/rosbridge_advertise_service_msg.h" |
25 | | -#include "messages/rosbridge_call_service_msg.h" |
26 | | -#include "messages/rosbridge_msg.h" |
27 | | -#include "messages/rosbridge_publish_msg.h" |
28 | | -#include "messages/rosbridge_service_response_msg.h" |
29 | | -#include "messages/rosbridge_subscribe_msg.h" |
30 | | -#include "messages/rosbridge_unadvertise_msg.h" |
31 | | -#include "messages/rosbridge_unadvertise_service_msg.h" |
32 | | -#include "messages/rosbridge_unsubscribe_msg.h" |
33 | | - |
34 | | -using json = rapidjson::Document; |
35 | | - |
36 | | -namespace rosbridge2cpp { |
37 | | - |
38 | | - /** |
39 | | - * The main rosbridge2cpp class that connects to the rosbridge server. |
40 | | - * The library is inspired by [roslibjs](http://wiki.ros.org/roslibjs), |
41 | | - * which is a feature-rich client-side implementation of the rosbridge protocol in java script. |
42 | | - */ |
43 | | - class ROSBridge { |
44 | | - |
45 | | - public: |
46 | | - ROSBridge(ITransportLayer &transport) : transport_layer_(transport) {} |
47 | | - |
48 | | - ROSBridge(ITransportLayer &transport, bool bson_only_mode) : transport_layer_(transport), bson_only_mode_(bson_only_mode) {} |
49 | | - |
50 | | - ~ROSBridge(); |
51 | | - |
52 | | - // Init the underlying transport layer and everything thats required |
53 | | - // to initialized in this class. |
54 | | - bool Init(std::string ip_addr, int port); |
55 | | - |
56 | | - bool IsHealthy() const; |
57 | | - |
58 | | - // Send arbitrary string-data over the given TransportLayer |
59 | | - bool SendMessage(std::string data); |
60 | | - |
61 | | - // Send json data over the transport layer, |
62 | | - // by serializing it and using |
63 | | - // ROSBridge::send_message(std::string data) |
64 | | - bool SendMessage(json &data); |
65 | | - |
66 | | - bool SendMessage(ROSBridgeMsg &msg); |
67 | | - |
68 | | - bool QueueMessage(const std::string& topic_name, int queue_size, ROSBridgePublishMsg& msg); |
69 | | - |
70 | | - |
71 | | - // Registration function for topic callbacks. |
72 | | - // This method should ONLY be called by ROSTopic instances. |
73 | | - // It will pass the received data to the registered std::function. |
74 | | - // |
75 | | - // Please note: |
76 | | - // _If you register more than one callback for the |
77 | | - // same topic, the old one get's overwritten_ |
78 | | - void RegisterTopicCallback(std::string topic_name, ROSCallbackHandle<FunVrROSPublishMsg>& callback_handle); |
79 | | - |
80 | | - // This method should ONLY be called by ROSTopic instances. |
81 | | - // If you call this on your own, the housekeeping in ROSTopic |
82 | | - // might fail which leads to missing unsubscribe messages etc. |
83 | | - // |
84 | | - // @return true, if the passed callback has been found and removed. false otherwise. |
85 | | - bool UnregisterTopicCallback(std::string topic_name, const ROSCallbackHandle<FunVrROSPublishMsg>& callback_handle); |
86 | | - |
87 | | - // Register the callback for a service call. |
88 | | - // This callback will be executed when we receive the response for a particular Service Request |
89 | | - void RegisterServiceCallback(std::string service_call_id, FunVrROSServiceResponseMsg fun); |
90 | | - |
91 | | - // Register the callback that shall be executed, |
92 | | - // whenever we receive a request for a service that |
93 | | - // this ROSBridge has advertised via a ROSService. |
94 | | - void RegisterServiceRequestCallback(std::string service_name, FunVrROSCallServiceMsgrROSServiceResponseMsgrAllocator fun); |
95 | | - void RegisterServiceRequestCallback(std::string service_name, FunVrROSCallServiceMsgrROSServiceResponseMsg fun); |
96 | | - |
97 | | - // An ID Counter that will be used to generate increasing |
98 | | - // IDs for service/topic etc. messages |
99 | | - long id_counter = 0; |
100 | | - |
101 | | - // Returns true if the bson only mode is activated |
102 | | - bool bson_only_mode() { |
103 | | - return bson_only_mode_; |
104 | | - } |
105 | | - |
106 | | - // Enable the BSON only mode. |
107 | | - // All communications with the rosbridge server |
108 | | - // will be in BSON, instead of JSON |
109 | | - void enable_bson_mode() { bson_only_mode_ = true; } |
110 | | - |
111 | | - private: |
112 | | - // Callback function for the used ITransportLayer. |
113 | | - // It receives the received json that was contained |
114 | | - // in the incoming ROSBridge packet |
115 | | - // |
116 | | - // @pre This method assumes a valid json variable |
117 | | - void IncomingMessageCallback(json &data); |
118 | | - |
119 | | - void IncomingMessageCallback(bson_t &bson); |
120 | | - |
121 | | - // Handler Method for reply packet |
122 | | - void HandleIncomingPublishMessage(ROSBridgePublishMsg &data); |
123 | | - |
124 | | - // Handler Method for reply packet |
125 | | - void HandleIncomingServiceResponseMessage(ROSBridgeServiceResponseMsg &data); |
126 | | - |
127 | | - // Handler Method for reply packet |
128 | | - void HandleIncomingServiceRequestMessage(ROSBridgeCallServiceMsg &data); |
129 | | - |
130 | | - int RunPublisherQueueThread(); |
131 | | - |
132 | | - ITransportLayer &transport_layer_; |
133 | | - std::unordered_map<std::string, std::list<ROSCallbackHandle<FunVrROSPublishMsg>>> registered_topic_callbacks_; |
134 | | - std::unordered_map<std::string, FunVrROSServiceResponseMsg> registered_service_callbacks_; |
135 | | - std::unordered_map<std::string, FunVrROSCallServiceMsgrROSServiceResponseMsgrAllocator> registered_service_request_callbacks_; |
136 | | - std::unordered_map<std::string, FunVrROSCallServiceMsgrROSServiceResponseMsg> registered_service_request_callbacks_bson_; |
137 | | - bool bson_only_mode_ = false; |
138 | | - |
139 | | - spinlock transport_layer_access_mutex_; |
140 | | - |
141 | | - spinlock change_topics_mutex_; |
142 | | - |
143 | | - std::thread publisher_queue_thread_; |
144 | | - spinlock change_publisher_queues_mutex_; |
145 | | - std::unordered_map<std::string, int> publisher_topics_; // points to index in publisher_queues_ |
146 | | - std::vector<std::queue<bson_t*>> publisher_queues_; // data to publish on the queue thread |
147 | | - int current_publisher_queue_ = 0; |
148 | | - bool run_publisher_queue_thread_ = true; |
149 | | - std::chrono::system_clock::time_point LastDataSendTime; // watchdog for send thread. Socket sometimes blocks infinitely. |
150 | | - }; |
151 | | -} |
| 1 | +#pragma once |
| 2 | + |
| 3 | +#include <iostream> |
| 4 | +#include <string> |
| 5 | +#include <thread> |
| 6 | +#include <functional> |
| 7 | +#include <unordered_map> |
| 8 | +#include <list> |
| 9 | +#include <queue> |
| 10 | +#include <chrono> |
| 11 | + |
| 12 | +#include <stdio.h> |
| 13 | +#include "types.h" |
| 14 | +#include "helper.h" |
| 15 | +#include "spinlock.h" |
| 16 | + |
| 17 | +#include "itransport_layer.h" |
| 18 | + |
| 19 | +#include "rapidjson/document.h" |
| 20 | +#include "rapidjson/writer.h" |
| 21 | +#include "rapidjson/stringbuffer.h" |
| 22 | + |
| 23 | +#include "messages/rosbridge_advertise_msg.h" |
| 24 | +#include "messages/rosbridge_advertise_service_msg.h" |
| 25 | +#include "messages/rosbridge_call_service_msg.h" |
| 26 | +#include "messages/rosbridge_msg.h" |
| 27 | +#include "messages/rosbridge_publish_msg.h" |
| 28 | +#include "messages/rosbridge_service_response_msg.h" |
| 29 | +#include "messages/rosbridge_subscribe_msg.h" |
| 30 | +#include "messages/rosbridge_unadvertise_msg.h" |
| 31 | +#include "messages/rosbridge_unadvertise_service_msg.h" |
| 32 | +#include "messages/rosbridge_unsubscribe_msg.h" |
| 33 | + |
| 34 | +using json = rapidjson::Document; |
| 35 | + |
| 36 | +namespace rosbridge2cpp { |
| 37 | + |
| 38 | + /** |
| 39 | + * The main rosbridge2cpp class that connects to the rosbridge server. |
| 40 | + * The library is inspired by [roslibjs](http://wiki.ros.org/roslibjs), |
| 41 | + * which is a feature-rich client-side implementation of the rosbridge protocol in java script. |
| 42 | + */ |
| 43 | + class ROSBridge { |
| 44 | + |
| 45 | + public: |
| 46 | + ROSBridge(ITransportLayer &transport) : transport_layer_(transport) {} |
| 47 | + |
| 48 | + ROSBridge(ITransportLayer &transport, bool bson_only_mode) : transport_layer_(transport), bson_only_mode_(bson_only_mode) {} |
| 49 | + |
| 50 | + ~ROSBridge(); |
| 51 | + |
| 52 | + // Init the underlying transport layer and everything thats required |
| 53 | + // to initialized in this class. |
| 54 | + bool Init(std::string ip_addr, int port); |
| 55 | + |
| 56 | + bool IsHealthy() const; |
| 57 | + |
| 58 | + // Send arbitrary string-data over the given TransportLayer |
| 59 | + bool SendMessage(std::string data); |
| 60 | + |
| 61 | + // Send json data over the transport layer, |
| 62 | + // by serializing it and using |
| 63 | + // ROSBridge::send_message(std::string data) |
| 64 | + bool SendMessage(json &data); |
| 65 | + |
| 66 | + bool SendMessage(ROSBridgeMsg &msg); |
| 67 | + |
| 68 | + bool QueueMessage(const std::string& topic_name, size_t queue_size, ROSBridgePublishMsg& msg); |
| 69 | + |
| 70 | + |
| 71 | + // Registration function for topic callbacks. |
| 72 | + // This method should ONLY be called by ROSTopic instances. |
| 73 | + // It will pass the received data to the registered std::function. |
| 74 | + // |
| 75 | + // Please note: |
| 76 | + // _If you register more than one callback for the |
| 77 | + // same topic, the old one get's overwritten_ |
| 78 | + void RegisterTopicCallback(std::string topic_name, ROSCallbackHandle<FunVrROSPublishMsg>& callback_handle); |
| 79 | + |
| 80 | + // This method should ONLY be called by ROSTopic instances. |
| 81 | + // If you call this on your own, the housekeeping in ROSTopic |
| 82 | + // might fail which leads to missing unsubscribe messages etc. |
| 83 | + // |
| 84 | + // @return true, if the passed callback has been found and removed. false otherwise. |
| 85 | + bool UnregisterTopicCallback(std::string topic_name, const ROSCallbackHandle<FunVrROSPublishMsg>& callback_handle); |
| 86 | + |
| 87 | + // Register the callback for a service call. |
| 88 | + // This callback will be executed when we receive the response for a particular Service Request |
| 89 | + void RegisterServiceCallback(std::string service_call_id, FunVrROSServiceResponseMsg fun); |
| 90 | + |
| 91 | + // Register the callback that shall be executed, |
| 92 | + // whenever we receive a request for a service that |
| 93 | + // this ROSBridge has advertised via a ROSService. |
| 94 | + void RegisterServiceRequestCallback(std::string service_name, FunVrROSCallServiceMsgrROSServiceResponseMsgrAllocator fun); |
| 95 | + void RegisterServiceRequestCallback(std::string service_name, FunVrROSCallServiceMsgrROSServiceResponseMsg fun); |
| 96 | + |
| 97 | + // An ID Counter that will be used to generate increasing |
| 98 | + // IDs for service/topic etc. messages |
| 99 | + long id_counter = 0; |
| 100 | + |
| 101 | + // Returns true if the bson only mode is activated |
| 102 | + bool bson_only_mode() { |
| 103 | + return bson_only_mode_; |
| 104 | + } |
| 105 | + |
| 106 | + // Enable the BSON only mode. |
| 107 | + // All communications with the rosbridge server |
| 108 | + // will be in BSON, instead of JSON |
| 109 | + void enable_bson_mode() { bson_only_mode_ = true; } |
| 110 | + |
| 111 | + private: |
| 112 | + // Callback function for the used ITransportLayer. |
| 113 | + // It receives the received json that was contained |
| 114 | + // in the incoming ROSBridge packet |
| 115 | + // |
| 116 | + // @pre This method assumes a valid json variable |
| 117 | + void IncomingMessageCallback(json &data); |
| 118 | + |
| 119 | + void IncomingMessageCallback(bson_t &bson); |
| 120 | + |
| 121 | + // Handler Method for reply packet |
| 122 | + void HandleIncomingPublishMessage(ROSBridgePublishMsg &data); |
| 123 | + |
| 124 | + // Handler Method for reply packet |
| 125 | + void HandleIncomingServiceResponseMessage(ROSBridgeServiceResponseMsg &data); |
| 126 | + |
| 127 | + // Handler Method for reply packet |
| 128 | + void HandleIncomingServiceRequestMessage(ROSBridgeCallServiceMsg &data); |
| 129 | + |
| 130 | + int RunPublisherQueueThread(); |
| 131 | + |
| 132 | + ITransportLayer &transport_layer_; |
| 133 | + std::unordered_map<std::string, std::list<ROSCallbackHandle<FunVrROSPublishMsg>>> registered_topic_callbacks_; |
| 134 | + std::unordered_map<std::string, FunVrROSServiceResponseMsg> registered_service_callbacks_; |
| 135 | + std::unordered_map<std::string, FunVrROSCallServiceMsgrROSServiceResponseMsgrAllocator> registered_service_request_callbacks_; |
| 136 | + std::unordered_map<std::string, FunVrROSCallServiceMsgrROSServiceResponseMsg> registered_service_request_callbacks_bson_; |
| 137 | + bool bson_only_mode_ = false; |
| 138 | + |
| 139 | + spinlock transport_layer_access_mutex_; |
| 140 | + |
| 141 | + spinlock change_topics_mutex_; |
| 142 | + |
| 143 | + std::thread publisher_queue_thread_; |
| 144 | + spinlock change_publisher_queues_mutex_; |
| 145 | + std::unordered_map<std::string, size_t> publisher_topics_; // points to index in publisher_queues_ |
| 146 | + std::vector<std::queue<bson_t*>> publisher_queues_; // data to publish on the queue thread |
| 147 | + size_t current_publisher_queue_ = 0; |
| 148 | + bool run_publisher_queue_thread_ = true; |
| 149 | + std::chrono::system_clock::time_point LastDataSendTime; // watchdog for send thread. Socket sometimes blocks infinitely. |
| 150 | + }; |
| 151 | +} |
0 commit comments