Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 """ The node provided by this file exposes a helper service used by
00037 the C++ rosserial_server. The service allows the C++ driver to look
00038 up message definitions and hash strings which would not have been
00039 known to it at compile time, allowing it to fully advertise topics
00040 originating from microcontrollers.
00041
00042 This allows rosserial_server to be distributed in binary form. """
00043
00044 import rospy
00045 from rosserial_msgs.srv import RequestMessageInfo
00046 from rosserial_msgs.srv import RequestServiceInfo
00047 from rosserial_python import load_message
00048 from rosserial_python import load_service
00049
00050
00051 class MessageInfoService(object):
00052 """ """
00053 def __init__(self):
00054 rospy.init_node("message_info_service")
00055 rospy.loginfo("rosserial message_info_service node")
00056 self.service = rospy.Service("message_info", RequestMessageInfo, self._message_info_cb)
00057 self.serviceInfoService = rospy.Service("service_info", RequestServiceInfo, self._service_info_cb)
00058 self.message_cache = {}
00059 self.service_cache = {}
00060
00061 def _message_info_cb(self, req):
00062 package_message = tuple(req.type.split("/"))
00063 if not self.message_cache.has_key(package_message):
00064 rospy.loginfo("Loading module to return info on %s/%s." % package_message)
00065 msg = load_message(*package_message)
00066 self.message_cache[package_message] = (msg._md5sum, msg._full_text)
00067 else:
00068 rospy.loginfo("Returning info from cache on %s/%s." % package_message)
00069 return self.message_cache[package_message]
00070
00071 def _service_info_cb(self, req):
00072 rospy.logdebug("req.service is %s" % req.service)
00073 package_service = tuple(req.service.split("/"))
00074 if not self.service_cache.has_key(package_service):
00075 rospy.loginfo("Loading module to return info on service %s/%s." % package_service)
00076 srv,mreq,mres = load_service(*package_service)
00077 self.service_cache[package_service] = (srv._md5sum,mreq._md5sum,mres._md5sum)
00078 else:
00079 rospy.loginfo("Returning info from cache on %s/%s." % package_service)
00080 return self.service_cache[package_service]
00081
00082 def spin(self):
00083 rospy.spin()
00084
00085 if __name__=="__main__":
00086 MessageInfoService().spin()