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 __author__ = "mferguson@willowgarage.com (Michael Ferguson)"
00037
00038 import roslib; roslib.load_manifest("rosserial_python")
00039 import rospy
00040
00041 import thread
00042 from serial import *
00043 import StringIO
00044
00045 from std_msgs.msg import Time
00046 from rosserial_msgs.msg import *
00047 from rosserial_msgs.srv import *
00048
00049 import time
00050 import struct
00051
00052 def load_pkg_module(package, directory):
00053
00054 in_path = False
00055 path = sys.path
00056 pkg_src = package+'/src'
00057
00058 for entry in sys.path:
00059 if pkg_src in entry:
00060 in_path = True
00061 if not in_path:
00062 roslib.load_manifest(package)
00063 try:
00064 m = __import__( package + '.' + directory )
00065 except:
00066 rospy.logerr( "Cannot import package : %s"% package )
00067 rospy.logerr( "sys.path was " + str(path) )
00068 return None
00069 return m
00070
00071 def load_message(package, message):
00072 m = load_pkg_module(package, 'msg')
00073 m2 = getattr(m, 'msg')
00074 return getattr(m2, message)
00075
00076 class Publisher:
00077 """
00078 Publisher forwards messages from the serial device to ROS.
00079 """
00080 def __init__(self, topic_info):
00081 """ Create a new publisher. """
00082 self.topic = topic_info.topic_name
00083
00084
00085 package, message = topic_info.message_type.split('/')
00086 self.message = load_message(package, message)
00087 if self.message._md5sum == topic_info.md5sum:
00088 self.publisher = rospy.Publisher(self.topic, self.message)
00089 else:
00090 raise Exception('Checksum does not match: ' + self.message._md5sum + ',' + topic_info.md5sum)
00091
00092 def handlePacket(self, data):
00093 """ Forward message to ROS network. """
00094 m = self.message()
00095 m.deserialize(data)
00096 self.publisher.publish(m)
00097
00098
00099 class Subscriber:
00100 """
00101 Subscriber forwards messages from ROS to the serial device.
00102 """
00103
00104 def __init__(self, topic_info, parent):
00105 self.topic = topic_info.topic_name
00106 self.id = topic_info.topic_id
00107 self.parent = parent
00108
00109
00110 package, message = topic_info.message_type.split('/')
00111 self.message = load_message(package, message)
00112 if self.message._md5sum == topic_info.md5sum:
00113 rospy.Subscriber(self.topic, self.message, self.callback)
00114 else:
00115 raise Exception('Checksum does not match: ' + self.message._md5sum + ',' + topic_info.md5sum)
00116
00117 def callback(self, msg):
00118 """ Forward message to serial device. """
00119 data_buffer = StringIO.StringIO()
00120 msg.serialize(data_buffer)
00121 self.parent.send(self.id, data_buffer.getvalue())
00122
00123
00124 class ServiceServer:
00125 """
00126 ServiceServer responds to requests from ROS.
00127 """
00128
00129 def __init__(self, topic_info, parent):
00130 self.topic = topic_info.topic_name
00131 self.parent = parent
00132
00133
00134 package, service = topic_info.message_type.split('/')
00135 s = load_pkg_module(package, 'srv')
00136 s = getattr(s, 'srv')
00137 self.mreq = getattr(s, service+"Request")
00138 self.mres = getattr(s, service+"Response")
00139 srv = getattr(s, service)
00140 self.service = rospy.Service(self.topic, srv, self.callback)
00141
00142
00143 self.data = None
00144
00145 def callback(self, req):
00146 """ Forward request to serial device. """
00147 data_buffer = StringIO.StringIO()
00148 req.serialize(data_buffer)
00149 self.response = None
00150 if self.parent.send(self.id, data_buffer.getvalue()) > 0:
00151 while self.response == None:
00152 pass
00153 return self.response
00154
00155 def handlePacket(self, data):
00156 """ Forward response to ROS network. """
00157 r = self.mres()
00158 r.deserialize(data)
00159 self.response = r
00160
00161
00162 class ServiceClient:
00163 """
00164 ServiceServer responds to requests from ROS.
00165 """
00166
00167 def __init__(self, topic_info, parent):
00168 self.topic = topic_info.topic_name
00169 self.parent = parent
00170
00171
00172 package, service = topic_info.message_type.split('/')
00173 s = load_pkg_module(package, 'srv')
00174 s = getattr(s, 'srv')
00175 self.mreq = getattr(s, service+"Request")
00176 self.mres = getattr(s, service+"Response")
00177 srv = getattr(s, service)
00178 rospy.loginfo("Starting service client, waiting for service '" + self.topic + "'")
00179 rospy.wait_for_service(self.topic)
00180 self.proxy = rospy.ServiceProxy(self.topic, srv)
00181
00182 def handlePacket(self, data):
00183 """ Forward request to ROS network. """
00184 req = self.mreq()
00185 req.deserialize(data)
00186
00187 resp = self.proxy(req)
00188
00189 data_buffer = StringIO.StringIO()
00190 resp.serialize(data_buffer)
00191 self.parent.send(self.id, data_buffer.getvalue())
00192
00193
00194 class SerialClient:
00195 """
00196 ServiceServer responds to requests from the serial device.
00197 """
00198
00199 def __init__(self, port=None, baud=57600, timeout=5.0):
00200 """ Initialize node, connect to bus, attempt to negotiate topics. """
00201 self.mutex = thread.allocate_lock()
00202
00203 self.lastsync = rospy.Time.now()
00204 self.timeout = timeout
00205
00206 if port== None:
00207
00208 pass
00209 elif hasattr(port, 'read'):
00210
00211 self.port=port
00212 else:
00213
00214 self.port = Serial(port, baud, timeout=self.timeout*0.5)
00215
00216 self.port.timeout = 0.01
00217
00218 time.sleep(0.1)
00219
00220 self.publishers = dict()
00221 self.subscribers = dict()
00222 self.services = dict()
00223
00224 self.buffer_out = -1
00225 self.buffer_in = -1
00226
00227 self.callbacks = dict()
00228
00229 self.callbacks[TopicInfo.ID_PUBLISHER] = self.setupPublisher
00230 self.callbacks[TopicInfo.ID_SUBSCRIBER] = self.setupSubscriber
00231
00232 self.callbacks[TopicInfo.ID_SERVICE_SERVER+TopicInfo.ID_PUBLISHER] = self.setupServiceServerPublisher
00233 self.callbacks[TopicInfo.ID_SERVICE_SERVER+TopicInfo.ID_SUBSCRIBER] = self.setupServiceServerSubscriber
00234 self.callbacks[TopicInfo.ID_SERVICE_CLIENT+TopicInfo.ID_PUBLISHER] = self.setupServiceClientPublisher
00235 self.callbacks[TopicInfo.ID_SERVICE_CLIENT+TopicInfo.ID_SUBSCRIBER] = self.setupServiceClientSubscriber
00236
00237 self.callbacks[TopicInfo.ID_PARAMETER_REQUEST] = self.handleParameterRequest
00238 self.callbacks[TopicInfo.ID_LOG] = self.handleLoggingRequest
00239 self.callbacks[TopicInfo.ID_TIME] = self.handleTimeRequest
00240
00241 rospy.sleep(2.0)
00242 self.requestTopics()
00243
00244 def requestTopics(self):
00245 """ Determine topics to subscribe/publish. """
00246 self.port.flushInput()
00247
00248 self.port.write("\xff\xff\x00\x00\x00\x00\xff")
00249
00250 def run(self):
00251 """ Forward recieved messages to appropriate publisher. """
00252 data = ''
00253 while not rospy.is_shutdown():
00254 if (rospy.Time.now() - self.lastsync).to_sec() > (self.timeout * 3):
00255 rospy.logerr("Lost sync with device, restarting...")
00256 self.requestTopics()
00257 self.lastsync = rospy.Time.now()
00258
00259 flag = [0,0]
00260 flag[0] = self.port.read(1)
00261 if (flag[0] != '\xff'):
00262 continue
00263 flag[1] = self.port.read(1)
00264 if ( flag[1] != '\xff'):
00265 rospy.loginfo("Failed Packet Flags ")
00266 continue
00267
00268 header = self.port.read(4)
00269 if (len(header) != 4):
00270
00271 continue
00272
00273 topic_id, msg_length = struct.unpack("<hh", header)
00274 msg = self.port.read(msg_length)
00275 if (len(msg) != msg_length):
00276 rospy.loginfo("Packet Failed : Failed to read msg data")
00277
00278 continue
00279 chk = self.port.read(1)
00280 checksum = sum(map(ord,header) ) + sum(map(ord, msg)) + ord(chk)
00281
00282 if checksum%256 == 255:
00283 try:
00284 self.callbacks[topic_id](msg)
00285 except KeyError:
00286 rospy.logerr("Tried to publish before configured, topic id %d" % topic_id)
00287 rospy.sleep(0.001)
00288
00289 def setPublishSize(self, bytes):
00290 if self.buffer_out < 0:
00291 self.buffer_out = bytes
00292 rospy.loginfo("Note: publish buffer size is %d bytes" % self.buffer_out)
00293
00294 def setSubscribeSize(self, bytes):
00295 if self.buffer_in < 0:
00296 self.buffer_in = bytes
00297 rospy.loginfo("Note: subscribe buffer size is %d bytes" % self.buffer_in)
00298
00299 def setupPublisher(self, data):
00300 """ Register a new publisher. """
00301 try:
00302 msg = TopicInfo()
00303 msg.deserialize(data)
00304 pub = Publisher(msg)
00305 self.publishers[msg.topic_id] = pub
00306 self.callbacks[msg.topic_id] = pub.handlePacket
00307 self.setPublishSize(msg.buffer_size)
00308 rospy.loginfo("Setup publisher on %s [%s]" % (msg.topic_name, msg.message_type) )
00309 except Exception as e:
00310 rospy.logerr("Creation of publisher failed: %s", e)
00311
00312 def setupSubscriber(self, data):
00313 """ Register a new subscriber. """
00314 try:
00315 msg = TopicInfo()
00316 msg.deserialize(data)
00317 sub = Subscriber(msg, self)
00318 self.subscribers[msg.topic_name] = sub
00319 self.setSubscribeSize(msg.buffer_size)
00320 rospy.loginfo("Setup subscriber on %s [%s]" % (msg.topic_name, msg.message_type) )
00321 except Exception as e:
00322 rospy.logerr("Creation of subscriber failed: %s", e)
00323
00324 def setupServiceServerPublisher(self, data):
00325 """ Register a new service server. """
00326 try:
00327 msg = TopicInfo()
00328 msg.deserialize(data)
00329 self.setPublishSize(msg.buffer_size)
00330 try:
00331 srv = self.services[msg.topic_name]
00332 except:
00333 srv = ServiceServer(msg, self)
00334 rospy.loginfo("Setup service server on %s [%s]" % (msg.topic_name, msg.message_type) )
00335 self.services[msg.topic_name] = srv
00336 if srv.mres._md5sum == msg.md5sum:
00337 self.callbacks[msg.topic_id] = srv.handlePacket
00338 else:
00339 raise Exception('Checksum does not match: ' + srv.res._md5sum + ',' + msg.md5sum)
00340 except Exception as e:
00341 rospy.logerr("Creation of service server failed: %s", e)
00342 def setupServiceServerSubscriber(self, data):
00343 """ Register a new service server. """
00344 try:
00345 msg = TopicInfo()
00346 msg.deserialize(data)
00347 self.setSubscribeSize(msg.buffer_size)
00348 try:
00349 srv = self.services[msg.topic_name]
00350 except:
00351 srv = ServiceServer(msg, self)
00352 rospy.loginfo("Setup service server on %s [%s]" % (msg.topic_name, msg.message_type) )
00353 self.services[msg.topic_name] = srv
00354 if srv.mreq._md5sum == msg.md5sum:
00355 srv.id = msg.topic_id
00356 else:
00357 raise Exception('Checksum does not match: ' + srv.req._md5sum + ',' + msg.md5sum)
00358 except Exception as e:
00359 rospy.logerr("Creation of service server failed: %s", e)
00360
00361 def setupServiceClientPublisher(self, data):
00362 """ Register a new service client. """
00363 try:
00364 msg = TopicInfo()
00365 msg.deserialize(data)
00366 self.setPublishSize(msg.buffer_size)
00367 try:
00368 srv = self.services[msg.topic_name]
00369 except:
00370 srv = ServiceClient(msg, self)
00371 rospy.loginfo("Setup service client on %s [%s]" % (msg.topic_name, msg.message_type) )
00372 self.services[msg.topic_name] = srv
00373 if srv.mreq._md5sum == msg.md5sum:
00374 self.callbacks[msg.topic_id] = srv.handlePacket
00375 else:
00376 raise Exception('Checksum does not match: ' + srv.req._md5sum + ',' + msg.md5sum)
00377 except Exception as e:
00378 rospy.logerr("Creation of service client failed: %s", e)
00379 def setupServiceClientSubscriber(self, data):
00380 """ Register a new service client. """
00381 try:
00382 msg = TopicInfo()
00383 msg.deserialize(data)
00384 self.setSubscribeSize(msg.buffer_size)
00385 try:
00386 srv = self.services[msg.topic_name]
00387 except:
00388 srv = ServiceClient(msg, self)
00389 rospy.loginfo("Setup service client on %s [%s]" % (msg.topic_name, msg.message_type) )
00390 self.services[msg.topic_name] = srv
00391 if srv.mres._md5sum == msg.md5sum:
00392 srv.id = msg.topic_id
00393 else:
00394 raise Exception('Checksum does not match: ' + srv.res._md5sum + ',' + msg.md5sum)
00395 except Exception as e:
00396 rospy.logerr("Creation of service client failed: %s", e)
00397
00398 def handleTimeRequest(self, data):
00399 """ Respond to device with system time. """
00400 t = Time()
00401 t.data = rospy.Time.now()
00402 data_buffer = StringIO.StringIO()
00403 t.serialize(data_buffer)
00404 self.send( TopicInfo.ID_TIME, data_buffer.getvalue() )
00405 self.lastsync = rospy.Time.now()
00406
00407 def handleParameterRequest(self, data):
00408 """ Send parameters to device. Supports only simple datatypes and arrays of such. """
00409 req = RequestParamRequest()
00410 req.deserialize(data)
00411 resp = RequestParamResponse()
00412 param = rospy.get_param(req.name)
00413 if param == None:
00414 rospy.logerr("Parameter %s does not exist"%req.name)
00415 return
00416 if (type(param) == dict):
00417 rospy.logerr("Cannot send param %s because it is a dictionary"%req.name)
00418 return
00419 if (type(param) != list):
00420 param = [param]
00421
00422 t = type(param[0])
00423 for p in param:
00424 if t!= type(p):
00425 rospy.logerr('All Paramers in the list %s must be of the same type'%req.name)
00426 return
00427 if (t == int):
00428 resp.ints= param
00429 if (t == float):
00430 resp.floats=param
00431 if (t == str):
00432 resp.strings = param
00433 print resp
00434 data_buffer = StringIO.StringIO()
00435 resp.serialize(data_buffer)
00436 self.send(TopicInfo.ID_PARAMETER_REQUEST, data_buffer.getvalue())
00437
00438 def handleLoggingRequest(self, data):
00439 """ Forward logging information from serial device into ROS. """
00440 msg = Log()
00441 msg.deserialize(data)
00442 if (msg.level == Log.DEBUG):
00443 rospy.logdebug(msg.msg)
00444 elif(msg.level== Log.INFO):
00445 rospy.loginfo(msg.msg)
00446 elif(msg.level== Log.WARN):
00447 rospy.logwarn(msg.msg)
00448 elif(msg.level== Log.ERROR):
00449 rospy.logerr(msg.msg)
00450 elif(msg.level==Log.FATAL):
00451 rospy.logfatal(msg.msg)
00452
00453 def send(self, topic, msg):
00454 """ Send a message on a particular topic to the device. """
00455 with self.mutex:
00456 length = len(msg)
00457 if self.buffer_in > 0 and length > self.buffer_in:
00458 rospy.logerr("Message from ROS network dropped: message larger than buffer.")
00459 print msg
00460 return -1
00461 else:
00462 checksum = 255 - ( ((topic&255) + (topic>>8) + (length&255) + (length>>8) + sum([ord(x) for x in msg]))%256 )
00463 data = '\xff\xff'+ chr(topic&255) + chr(topic>>8) + chr(length&255) + chr(length>>8)
00464 data = data + msg + chr(checksum)
00465 self.port.write(data)
00466 return length
00467