35 #ifndef ROSSERIAL_SERVER_SESSION_H
36 #define ROSSERIAL_SERVER_SESSION_H
39 #include <boost/bind.hpp>
40 #include <boost/asio.hpp>
41 #include <boost/function.hpp>
45 #include <rosserial_msgs/TopicInfo.h>
46 #include <rosserial_msgs/Log.h>
48 #include <std_msgs/Time.h>
59 template<
typename Socket>
63 Session(boost::asio::io_service& io_service)
71 boost::asio::placeholders::error))
90 boost::asio::placeholders::error));
102 callbacks_[rosserial_msgs::TopicInfo::ID_PUBLISHER]
104 callbacks_[rosserial_msgs::TopicInfo::ID_SUBSCRIBER]
106 callbacks_[rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT+rosserial_msgs::TopicInfo::ID_PUBLISHER]
108 callbacks_[rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT+rosserial_msgs::TopicInfo::ID_SUBSCRIBER]
112 callbacks_[rosserial_msgs::TopicInfo::ID_TIME]
179 boost::asio::placeholders::error));
215 uint16_t topic_id, length;
216 uint8_t length_checksum;
219 stream >> length >> length_checksum;
220 if (length_checksum +
checksum(length) != 0xff) {
222 ROS_WARN(
"Bad message header length checksum. Dropping message from client. T%d L%d C%d %d", topic_id, length, length_checksum, csl);
228 ROS_DEBUG(
"Received message header with length %d and topic_id=%d", length, topic_id);
236 ROS_DEBUG(
"Received body of length %d for message on topic %d.", stream.
getLength(), topic_id);
241 if (msg_checksum != 0xff) {
242 ROS_WARN(
"Rejecting message on topicId=%d, length=%d with bad checksum.", topic_id, stream.
getLength());
250 if (topic_id < 100) {
251 ROS_ERROR(
"Buffer overrun when attempting to parse setup message.");
254 ROS_WARN(
"Buffer overrun when attempting to parse user message.");
258 ROS_WARN(
"Received message with unrecognized topicId (%d).", topic_id);
264 ROS_WARN(
"Unrecognised topic threshold exceeded. Requesting topics from client");
276 if (error == boost::system::errc::no_buffer_space) {
278 ROS_WARN(
"Overrun on receive buffer. Attempting to regain rx sync.");
291 uint8_t overhead_bytes = 8;
292 uint16_t length = overhead_bytes + message.size();
295 uint8_t msg_checksum;
299 uint8_t msg_len_checksum = 255 -
checksum(message.size());
300 stream << (uint16_t)0xfeff << (uint16_t)message.size() << msg_len_checksum << topic_id;
303 memcpy(stream.
advance(message.size()), &message[0], message.size());
304 stream << msg_checksum;
306 ROS_DEBUG_NAMED(
"async_write",
"Sending buffer of %d bytes to client.", length);
307 boost::asio::async_write(
socket_, boost::asio::buffer(*buffer_ptr),
314 if (error == boost::system::errc::io_error) {
316 }
else if (error == boost::system::errc::no_such_device) {
338 boost::asio::placeholders::error));
347 if (error != boost::asio::error::operation_aborted) {
355 std::vector<uint8_t> message(0);
356 ROS_DEBUG(
"Sending request topics message for VER2 protocol.");
357 write_message(message, rosserial_msgs::TopicInfo::ID_PUBLISHER);
363 boost::asio::placeholders::error));
367 if (error != boost::asio::error::operation_aborted) {
371 ROS_WARN(
"Connected client failed to establish the publishers and subscribers dictated by require parameter. Re-requesting topics.");
383 for (
int i = 0; i < param_list.
size(); ++i) {
385 std::string required_topic((std::string(param_list[i])));
388 for (
typename M::iterator j = map.begin(); j != map.end(); ++j) {
392 ROS_INFO_STREAM(
"Verified connection to topic " << required_topic <<
", given in parameter " << param_name);
397 ROS_WARN_STREAM(
"Missing connection to topic " << required_topic <<
", required by parameter " << param_name);
406 for (uint16_t i = 0; i < stream.
getLength(); ++i) {
413 return (val >> 8) + val;
419 rosserial_msgs::TopicInfo topic_info;
430 rosserial_msgs::TopicInfo topic_info;
447 rosserial_msgs::TopicInfo topic_info;
450 if (!
services_.count(topic_info.topic_name)) {
451 ROS_DEBUG(
"Creating service client for topic %s",topic_info.topic_name.c_str());
457 if (
services_[topic_info.topic_name]->getRequestMessageMD5() != topic_info.md5sum) {
458 ROS_WARN(
"Service client setup: Request message MD5 mismatch between rosserial client and ROS");
460 ROS_DEBUG(
"Service client %s: request message MD5 successfully validated as %s",
461 topic_info.topic_name.c_str(),topic_info.md5sum.c_str());
467 rosserial_msgs::TopicInfo topic_info;
470 if (!
services_.count(topic_info.topic_name)) {
471 ROS_DEBUG(
"Creating service client for topic %s",topic_info.topic_name.c_str());
478 services_[topic_info.topic_name]->setTopicId(topic_info.topic_id);
479 if (
services_[topic_info.topic_name]->getResponseMessageMD5() != topic_info.md5sum) {
480 ROS_WARN(
"Service client setup: Response message MD5 mismatch between rosserial client and ROS");
482 ROS_DEBUG(
"Service client %s: response message MD5 successfully validated as %s",
483 topic_info.topic_name.c_str(),topic_info.md5sum.c_str());
489 rosserial_msgs::Log l;
491 if(l.level == rosserial_msgs::Log::ROSDEBUG)
ROS_DEBUG(
"%s", l.msg.c_str());
492 else if(l.level == rosserial_msgs::Log::INFO)
ROS_INFO(
"%s", l.msg.c_str());
493 else if(l.level == rosserial_msgs::Log::WARN)
ROS_WARN(
"%s", l.msg.c_str());
494 else if(l.level == rosserial_msgs::Log::ERROR)
ROS_ERROR(
"%s", l.msg.c_str());
495 else if(l.level == rosserial_msgs::Log::FATAL)
ROS_FATAL(
"%s", l.msg.c_str());
503 std::vector<uint8_t> message(length);
543 #endif // ROSSERIAL_SERVER_SESSION_H