Go to the documentation of this file.00001
00035 #ifndef ROSSERIAL_SERVER_TOPIC_HANDLERS_H
00036 #define ROSSERIAL_SERVER_TOPIC_HANDLERS_H
00037
00038 #include <ros/ros.h>
00039 #include <rosserial_msgs/TopicInfo.h>
00040 #include <rosserial_msgs/RequestMessageInfo.h>
00041 #include <rosserial_msgs/RequestServiceInfo.h>
00042 #include <topic_tools/shape_shifter.h>
00043
00044 namespace rosserial_server
00045 {
00046
00047 class Publisher {
00048 public:
00049 Publisher(ros::NodeHandle& nh, const rosserial_msgs::TopicInfo& topic_info) {
00050 if (!message_service_.isValid()) {
00051
00052 message_service_ = nh.serviceClient<rosserial_msgs::RequestMessageInfo>("message_info");
00053 if (!message_service_.waitForExistence(ros::Duration(5.0))) {
00054 ROS_WARN("Timed out waiting for message_info service to become available.");
00055 }
00056 }
00057
00058 rosserial_msgs::RequestMessageInfo info;
00059 info.request.type = topic_info.message_type;
00060 if (message_service_.call(info)) {
00061 if (info.response.md5 != topic_info.md5sum) {
00062 ROS_WARN_STREAM("Message" << topic_info.message_type << "MD5 sum from client does not match that in system. Will avoid using system's message definition.");
00063 info.response.definition = "";
00064 }
00065 } else {
00066 ROS_WARN("Failed to call message_info service. Proceeding without full message definition.");
00067 }
00068
00069 message_.morph(topic_info.md5sum, topic_info.message_type, info.response.definition, "false");
00070 publisher_ = message_.advertise(nh, topic_info.topic_name, 1);
00071 }
00072
00073 void handle(ros::serialization::IStream stream) {
00074 ros::serialization::Serializer<topic_tools::ShapeShifter>::read(stream, message_);
00075 publisher_.publish(message_);
00076 }
00077
00078 std::string get_topic() {
00079 return publisher_.getTopic();
00080 }
00081
00082 private:
00083 ros::Publisher publisher_;
00084 topic_tools::ShapeShifter message_;
00085
00086 static ros::ServiceClient message_service_;
00087 };
00088
00089 ros::ServiceClient Publisher::message_service_;
00090 typedef boost::shared_ptr<Publisher> PublisherPtr;
00091
00092
00093 class Subscriber {
00094 public:
00095 Subscriber(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
00096 boost::function<void(std::vector<uint8_t>& buffer)> write_fn)
00097 : write_fn_(write_fn) {
00098 ros::SubscribeOptions opts;
00099 opts.init<topic_tools::ShapeShifter>(
00100 topic_info.topic_name, 1, boost::bind(&Subscriber::handle, this, _1));
00101 opts.md5sum = topic_info.md5sum;
00102 opts.datatype = topic_info.message_type;
00103 subscriber_ = nh.subscribe(opts);
00104 }
00105
00106 std::string get_topic() {
00107 return subscriber_.getTopic();
00108 }
00109
00110 private:
00111 void handle(const boost::shared_ptr<topic_tools::ShapeShifter const>& msg) {
00112 size_t length = ros::serialization::serializationLength(*msg);
00113 std::vector<uint8_t> buffer(length);
00114
00115 ros::serialization::OStream ostream(&buffer[0], length);
00116 ros::serialization::Serializer<topic_tools::ShapeShifter>::write(ostream, *msg);
00117
00118 write_fn_(buffer);
00119 }
00120
00121 ros::Subscriber subscriber_;
00122 boost::function<void(std::vector<uint8_t>& buffer)> write_fn_;
00123 };
00124
00125 typedef boost::shared_ptr<Subscriber> SubscriberPtr;
00126
00127 class ServiceClient {
00128 public:
00129 ServiceClient(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
00130 boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn)
00131 : write_fn_(write_fn) {
00132 topic_id_ = -1;
00133 if (!service_info_service_.isValid()) {
00134
00135 service_info_service_ = nh.serviceClient<rosserial_msgs::RequestServiceInfo>("service_info");
00136 if (!service_info_service_.waitForExistence(ros::Duration(5.0))) {
00137 ROS_WARN("Timed out waiting for service_info service to become available.");
00138 }
00139 }
00140
00141 rosserial_msgs::RequestServiceInfo info;
00142 info.request.service = topic_info.message_type;
00143 ROS_DEBUG("Calling service_info service for topic name %s",topic_info.topic_name.c_str());
00144 if (service_info_service_.call(info)) {
00145 request_message_md5_ = info.response.request_md5;
00146 response_message_md5_ = info.response.response_md5;
00147 } else {
00148 ROS_WARN("Failed to call service_info service. The service client will be created with blank md5sum.");
00149 }
00150 ros::ServiceClientOptions opts;
00151 opts.service = topic_info.topic_name;
00152 opts.md5sum = service_md5_ = info.response.service_md5;
00153 opts.persistent = false;
00154 service_client_ = nh.serviceClient(opts);
00155 }
00156 void setTopicId(uint16_t topic_id) {
00157 topic_id_ = topic_id;
00158 }
00159 std::string getRequestMessageMD5() {
00160 return request_message_md5_;
00161 }
00162 std::string getResponseMessageMD5() {
00163 return response_message_md5_;
00164 }
00165
00166 void handle(ros::serialization::IStream stream) {
00167
00168 ros::serialization::Serializer<topic_tools::ShapeShifter>::read(stream, request_message_);
00169
00170
00171
00172
00173 service_client_.call(request_message_, response_message_, service_md5_);
00174
00175
00176 size_t length = ros::serialization::serializationLength(response_message_);
00177 std::vector<uint8_t> buffer(length);
00178 ros::serialization::OStream ostream(&buffer[0], length);
00179 ros::serialization::Serializer<topic_tools::ShapeShifter>::write(ostream, response_message_);
00180 write_fn_(buffer,topic_id_);
00181 }
00182
00183 private:
00184 topic_tools::ShapeShifter request_message_;
00185 topic_tools::ShapeShifter response_message_;
00186 ros::ServiceClient service_client_;
00187 static ros::ServiceClient service_info_service_;
00188 boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn_;
00189 std::string service_md5_;
00190 std::string request_message_md5_;
00191 std::string response_message_md5_;
00192 uint16_t topic_id_;
00193 };
00194
00195 ros::ServiceClient ServiceClient::service_info_service_;
00196 typedef boost::shared_ptr<ServiceClient> ServiceClientPtr;
00197
00198 }
00199
00200 #endif // ROSSERIAL_SERVER_TOPIC_HANDLERS_H