SerialClient.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #####################################################################
00004 # Software License Agreement (BSD License)
00005 #
00006 # Copyright (c) 2011, Willow Garage, Inc.
00007 # All rights reserved.
00008 #
00009 # Redistribution and use in source and binary forms, with or without
00010 # modification, are permitted provided that the following conditions
00011 # are met:
00012 #
00013 #  * Redistributions of source code must retain the above copyright
00014 #    notice, this list of conditions and the following disclaimer.
00015 #  * Redistributions in binary form must reproduce the above
00016 #    copyright notice, this list of conditions and the following
00017 #    disclaimer in the documentation and/or other materials provided
00018 #    with the distribution.
00019 #  * Neither the name of Willow Garage, Inc. nor the names of its
00020 #    contributors may be used to endorse or promote products derived
00021 #    from this software without specific prior written permission.
00022 #
00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 # POSSIBILITY OF SUCH DAMAGE.
00035 
00036 __author__ = "mferguson@willowgarage.com (Michael Ferguson)"
00037 
00038 import roslib;
00039 import rospy
00040 
00041 import thread
00042 import multiprocessing
00043 from serial import *
00044 import StringIO
00045 
00046 from std_msgs.msg import Time
00047 from rosserial_msgs.msg import *
00048 from rosserial_msgs.srv import *
00049 
00050 import diagnostic_msgs.msg
00051 
00052 import socket
00053 import time
00054 import struct
00055 import signal
00056 
00057 def load_pkg_module(package, directory):
00058     #check if its in the python path
00059     in_path = False
00060     path = sys.path
00061     pkg_src = package+'/src' #check for the source directory which
00062                              # is added to path by roslib boostrapping
00063     for entry in sys.path:
00064         if pkg_src in entry:
00065             in_path = True
00066     if not in_path:
00067         roslib.load_manifest(package)
00068     try:
00069         m = __import__( package + '.' + directory )
00070     except:
00071         rospy.logerr( "Cannot import package : %s"% package )
00072         rospy.logerr( "sys.path was " + str(path) )
00073         return None
00074     return m
00075 
00076 def load_message(package, message):
00077     m = load_pkg_module(package, 'msg')
00078     m2 = getattr(m, 'msg')
00079     return getattr(m2, message)
00080 
00081 class Publisher:
00082     """
00083         Publisher forwards messages from the serial device to ROS.
00084     """
00085     def __init__(self, topic_info):
00086         """ Create a new publisher. """
00087         self.topic = topic_info.topic_name
00088 
00089         # find message type
00090         package, message = topic_info.message_type.split('/')
00091         self.message = load_message(package, message)
00092         if self.message._md5sum == topic_info.md5sum:
00093             self.publisher = rospy.Publisher(self.topic, self.message)
00094         else:
00095             raise Exception('Checksum does not match: ' + self.message._md5sum + ',' + topic_info.md5sum)
00096 
00097     def handlePacket(self, data):
00098         """ Forward message to ROS network. """
00099         m = self.message()
00100         m.deserialize(data)
00101         self.publisher.publish(m)
00102 
00103 
00104 class Subscriber:
00105     """
00106         Subscriber forwards messages from ROS to the serial device.
00107     """
00108 
00109     def __init__(self, topic_info, parent):
00110         self.topic = topic_info.topic_name
00111         self.id = topic_info.topic_id
00112         self.parent = parent
00113 
00114         # find message type
00115         package, message = topic_info.message_type.split('/')
00116         self.message = load_message(package, message)
00117         if self.message._md5sum == topic_info.md5sum:
00118             self.subscriber = rospy.Subscriber(self.topic, self.message, self.callback)
00119         else:
00120             raise Exception('Checksum does not match: ' + self.message._md5sum + ',' + topic_info.md5sum)
00121 
00122     def unregister(self):
00123         rospy.loginfo("Removing subscriber: %s", self.topic)
00124         self.subscriber.unregister()            
00125 
00126     def callback(self, msg):
00127         """ Forward message to serial device. """
00128         data_buffer = StringIO.StringIO()
00129         msg.serialize(data_buffer)
00130         self.parent.send(self.id, data_buffer.getvalue())
00131 
00132     def unregister(self):
00133         self.subscriber.unregister()
00134 
00135 class ServiceServer:
00136     """
00137         ServiceServer responds to requests from ROS.
00138     """
00139 
00140     def __init__(self, topic_info, parent):
00141         self.topic = topic_info.topic_name
00142         self.parent = parent
00143 
00144         # find message type
00145         package, service = topic_info.message_type.split('/')
00146         s = load_pkg_module(package, 'srv')
00147         s = getattr(s, 'srv')
00148         self.mreq = getattr(s, service+"Request")
00149         self.mres = getattr(s, service+"Response")
00150         srv = getattr(s, service)
00151         self.service = rospy.Service(self.topic, srv, self.callback)
00152 
00153         # response message
00154         self.data = None
00155 
00156     def unregister(self):
00157         rospy.loginfo("Removing service: %s", self.topic)
00158         self.service.shutdown()                    
00159 
00160     def callback(self, req):
00161         """ Forward request to serial device. """
00162         data_buffer = StringIO.StringIO()
00163         req.serialize(data_buffer)
00164         self.response = None
00165         if self.parent.send(self.id, data_buffer.getvalue()) >= 0:
00166             while self.response == None:
00167                 pass
00168         return self.response
00169 
00170     def handlePacket(self, data):
00171         """ Forward response to ROS network. """
00172         r = self.mres()
00173         r.deserialize(data)
00174         self.response = r
00175 
00176 
00177 class ServiceClient:
00178     """
00179         ServiceServer responds to requests from ROS.
00180     """
00181 
00182     def __init__(self, topic_info, parent):
00183         self.topic = topic_info.topic_name
00184         self.parent = parent
00185 
00186         # find message type
00187         package, service = topic_info.message_type.split('/')
00188         s = load_pkg_module(package, 'srv')
00189         s = getattr(s, 'srv')
00190         self.mreq = getattr(s, service+"Request")
00191         self.mres = getattr(s, service+"Response")
00192         srv = getattr(s, service)
00193         rospy.loginfo("Starting service client, waiting for service '" + self.topic + "'")
00194         rospy.wait_for_service(self.topic)
00195         self.proxy = rospy.ServiceProxy(self.topic, srv)
00196 
00197     def handlePacket(self, data):
00198         """ Forward request to ROS network. """
00199         req = self.mreq()
00200         req.deserialize(data)
00201         # call service proxy
00202         resp = self.proxy(req)
00203         # serialize and publish
00204         data_buffer = StringIO.StringIO()
00205         resp.serialize(data_buffer)
00206         self.parent.send(self.id, data_buffer.getvalue())
00207 
00208 class RosSerialServer:
00209     """
00210         RosSerialServer waits for a socket connection then passes itself, forked as a
00211         new process, to SerialClient which uses it as a serial port. It continues to listen
00212         for additional connections. Each forked process is a new ros node, and proxies ros
00213         operations (e.g. publish/subscribe) from its connection to the rest of ros.
00214     """
00215     def __init__(self, tcp_portnum, fork_server=False):
00216         print "Fork_server is: ", fork_server
00217         self.tcp_portnum = tcp_portnum
00218         self.fork_server = fork_server
00219 
00220     def listen(self):
00221         self.serversocket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
00222         #bind the socket to a public host, and a well-known port
00223         self.serversocket.bind(("", self.tcp_portnum)) #become a server socket
00224         self.serversocket.listen(1)
00225 
00226         while True:
00227             #accept connections
00228             print "waiting for socket connection"
00229             (clientsocket, address) = self.serversocket.accept()
00230 
00231             #now do something with the clientsocket
00232             rospy.loginfo("Established a socket connection from %s on port %s" % (address))
00233             self.socket = clientsocket
00234             self.isConnected = True
00235 
00236             if (self.fork_server == True):      # if configured to launch server in a separate process
00237                 rospy.loginfo("Forking a socket server process")
00238                 process = multiprocessing.Process(target=self.startSocketServer, args=(address))
00239                 process.daemon = True
00240                 process.start()
00241                 rospy.loginfo("launched startSocketServer")
00242             else:
00243                 rospy.loginfo("calling startSerialClient")
00244                 self.startSerialClient()
00245                 rospy.loginfo("startSerialClient() exited")
00246 
00247     def startSerialClient(self):
00248         client = SerialClient(self)
00249         try:
00250             client.run()
00251         except KeyboardInterrupt:
00252             pass
00253         except RuntimeError:
00254             rospy.loginfo("RuntimeError exception caught")
00255             self.isConnected = False
00256         except socket.error:
00257             rospy.loginfo("socket.error exception caught")
00258             self.isConnected = False
00259         finally:
00260             self.socket.close()
00261             for sub in client.subscribers.values():
00262                 sub.unregister()
00263             for srv in client.services.values():
00264                 srv.unregister()
00265             #pass
00266 
00267     def startSocketServer(self, port, address):
00268         rospy.loginfo("starting ROS Serial Python Node serial_node-%r" % (address,))
00269         rospy.init_node("serial_node_%r" % (address,))
00270         self.startSerialClient()
00271      
00272     def flushInput(self):
00273          pass
00274 
00275     def write(self, data):
00276         if (self.isConnected == False):
00277             return
00278         length = len(data)
00279         totalsent = 0
00280 
00281         while totalsent < length:
00282             sent = self.socket.send(data[totalsent:])
00283             if sent == 0:
00284                 raise RuntimeError("RosSerialServer.write() socket connection broken")
00285             totalsent = totalsent + sent
00286 
00287     def read(self, rqsted_length):
00288         self.msg = ''
00289         if (self.isConnected == False):
00290             return self.msg
00291 
00292         while len(self.msg) < rqsted_length:
00293             chunk = self.socket.recv(rqsted_length - len(self.msg))
00294             if chunk == '':
00295                 raise RuntimeError("RosSerialServer.read() socket connection broken")
00296             self.msg = self.msg + chunk
00297         return self.msg
00298 
00299     def close(self):
00300         self.port.close()
00301         
00302     def inWaiting(self):
00303         try: # the caller checks just for <1, so we'll peek at just one byte
00304             chunk = self.socket.recv(1, socket.MSG_DONTWAIT|socket.MSG_PEEK)
00305             if chunk == '':
00306                 raise RuntimeError("RosSerialServer.inWaiting() socket connection broken")
00307             return len(chunk)
00308         except socket.error, e:
00309             if e.args[0] == errno.EWOULDBLOCK:
00310                 return 0
00311             raise
00312 
00313 
00314 class SerialClient:
00315     """
00316         ServiceServer responds to requests from the serial device.
00317     """
00318 
00319     def __init__(self, port=None, baud=57600, timeout=5.0):
00320         """ Initialize node, connect to bus, attempt to negotiate topics. """
00321         self.mutex = thread.allocate_lock()
00322 
00323         self.lastsync = rospy.Time(0)
00324         self.lastsync_lost = rospy.Time(0)
00325         self.timeout = timeout
00326         self.synced = False
00327 
00328         self.pub_diagnostics = rospy.Publisher('/diagnostics', diagnostic_msgs.msg.DiagnosticArray)
00329 
00330         if port== None:
00331             # no port specified, listen for any new port?
00332             pass
00333         elif hasattr(port, 'read'):
00334             #assume its a filelike object
00335             self.port=port
00336         else:
00337             # open a specific port
00338             try:
00339                 self.port = Serial(port, baud, timeout=self.timeout*0.5)
00340             except SerialException as e:
00341                 rospy.logerr("Error opening serial: %s", e)
00342                 rospy.signal_shutdown("Error opening serial: %s" % e)
00343                 raise SystemExit
00344 
00345         self.port.timeout = 0.01  # Edit the port timeout
00346 
00347         time.sleep(0.1)           # Wait for ready (patch for Uno)
00348 
00349         # hydro introduces protocol ver2 which must match node_handle.h
00350         # The protocol version is sent as the 2nd sync byte emitted by each end
00351         self.protocol_ver1 = '\xff'
00352         self.protocol_ver2 = '\xfe'
00353         self.protocol_ver = self.protocol_ver2
00354 
00355         self.publishers = dict()  # id:Publishers
00356         self.subscribers = dict() # topic:Subscriber
00357         self.services = dict()    # topic:Service
00358 
00359         self.buffer_out = -1
00360         self.buffer_in = -1
00361 
00362         self.callbacks = dict()
00363         # endpoints for creating new pubs/subs
00364         self.callbacks[TopicInfo.ID_PUBLISHER] = self.setupPublisher
00365         self.callbacks[TopicInfo.ID_SUBSCRIBER] = self.setupSubscriber
00366         # service client/servers have 2 creation endpoints (a publisher and a subscriber)
00367         self.callbacks[TopicInfo.ID_SERVICE_SERVER+TopicInfo.ID_PUBLISHER] = self.setupServiceServerPublisher
00368         self.callbacks[TopicInfo.ID_SERVICE_SERVER+TopicInfo.ID_SUBSCRIBER] = self.setupServiceServerSubscriber
00369         self.callbacks[TopicInfo.ID_SERVICE_CLIENT+TopicInfo.ID_PUBLISHER] = self.setupServiceClientPublisher
00370         self.callbacks[TopicInfo.ID_SERVICE_CLIENT+TopicInfo.ID_SUBSCRIBER] = self.setupServiceClientSubscriber
00371         # custom endpoints
00372         self.callbacks[TopicInfo.ID_PARAMETER_REQUEST] = self.handleParameterRequest
00373         self.callbacks[TopicInfo.ID_LOG] = self.handleLoggingRequest
00374         self.callbacks[TopicInfo.ID_TIME] = self.handleTimeRequest
00375 
00376         rospy.sleep(2.0) # TODO
00377         self.requestTopics()
00378         self.lastsync = rospy.Time.now()
00379 
00380         signal.signal(signal.SIGINT, self.txStopRequest)
00381 
00382     def requestTopics(self):
00383         """ Determine topics to subscribe/publish. """
00384         self.port.flushInput()
00385         # request topic sync
00386         self.port.write("\xff" + self.protocol_ver + "\x00\x00\xff\x00\x00\xff")
00387 
00388     def txStopRequest(self, signal, frame):
00389         """ send stop tx request to arduino when receive SIGINT(Ctrl-c)"""
00390         self.port.flushInput()
00391         self.port.write("\xff" + self.protocol_ver + "\x00\x00\xff\x0b\x00\xf4") 
00392         # tx_stop_request is x0b
00393         rospy.loginfo("Send tx stop request")
00394         sys.exit(0)
00395 
00396     def tryRead(self, length):
00397         try:
00398             bytes_read = self.port.read(length)
00399             if len(bytes_read) < length:
00400                 rospy.logwarn("Serial Port read returned short (expected %d bytes, received %d instead)."
00401                               % (length, len(bytes_read)))
00402                 raise IOError()
00403             return bytes_read
00404         except Exception as e:
00405             rospy.logwarn("Serial Port read failure: %s", e)
00406             raise IOError()
00407 
00408     def run(self):
00409         """ Forward recieved messages to appropriate publisher. """
00410         data = ''
00411         while not rospy.is_shutdown():
00412             if (rospy.Time.now() - self.lastsync).to_sec() > (self.timeout * 3):
00413                 if (self.synced == True):
00414                     rospy.logerr("Lost sync with device, restarting...")
00415                 else:
00416                     rospy.logerr("Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino")
00417                 self.lastsync_lost = rospy.Time.now()
00418                 self.sendDiagnostics(diagnostic_msgs.msg.DiagnosticStatus.ERROR, "no sync with device")
00419                 self.requestTopics()
00420                 self.lastsync = rospy.Time.now()
00421 
00422             # This try-block is here because we make multiple calls to read(). Any one of them can throw
00423             # an IOError if there's a serial problem or timeout. In that scenario, a single handler at the
00424             # bottom attempts to reconfigure the topics.
00425             try:
00426                 if self.port.inWaiting() < 1:
00427                     time.sleep(0.001)
00428                     continue
00429 
00430                 flag = [0,0]
00431                 flag[0] = self.tryRead(1)
00432                 if (flag[0] != '\xff'):                
00433                     continue
00434 
00435                 flag[1] = self.tryRead(1) 
00436                 if ( flag[1] != self.protocol_ver):
00437                     self.sendDiagnostics(diagnostic_msgs.msg.DiagnosticStatus.ERROR, "Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client")
00438                     rospy.logerr("Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client")
00439                     protocol_ver_msgs = {'\xff': 'Rev 0 (rosserial 0.4 and earlier)', '\xfe': 'Rev 1 (rosserial 0.5+)', '\xfd': 'Some future rosserial version'}
00440                     if (flag[1] in protocol_ver_msgs):
00441                         found_ver_msg = 'Protocol version of client is ' + protocol_ver_msgs[flag[1]]
00442                     else:
00443                         found_ver_msg = "Protocol version of client is unrecognized"
00444                     rospy.loginfo("%s, expected %s" % (found_ver_msg, protocol_ver_msgs[self.protocol_ver]))
00445                     continue
00446 
00447                 msg_len_bytes = self.tryRead(2)
00448                 msg_length, = struct.unpack("<h", msg_len_bytes)
00449      
00450                 msg_len_chk = self.tryRead(1)
00451                 msg_len_checksum = sum(map(ord, msg_len_bytes)) + ord(msg_len_chk)
00452 
00453                 if msg_len_checksum % 256 != 255:
00454                     rospy.loginfo("wrong checksum for msg length, length %d" %(msg_length))
00455                     rospy.loginfo("chk is %d" % ord(msg_len_chk))
00456                     continue
00457 
00458                 # topic id (2 bytes)
00459                 topic_id_header = self.tryRead(2)
00460                 topic_id, = struct.unpack("<h", topic_id_header)
00461 
00462                 try:
00463                     msg = self.tryRead(msg_length)
00464                 except IOError:
00465                     self.sendDiagnostics(diagnostic_msgs.msg.DiagnosticStatus.ERROR, "Packet Failed : Failed to read msg data")
00466                     rospy.loginfo("Packet Failed :  Failed to read msg data")
00467                     rospy.loginfo("msg len is %d",len(msg))
00468                     raise
00469 
00470                 # checksum for topic id and msg
00471                 chk = self.tryRead(1)
00472                 checksum = sum(map(ord, topic_id_header) ) + sum(map(ord, msg)) + ord(chk)
00473 
00474                 if checksum % 256 == 255:
00475                     self.synced = True
00476                     try:
00477                         self.callbacks[topic_id](msg)
00478                     except KeyError:
00479                         rospy.logerr("Tried to publish before configured, topic id %d" % topic_id)
00480                     rospy.sleep(0.001)
00481                 else:
00482                     rospy.loginfo("wrong checksum for topic id and msg")
00483 
00484             except IOError:
00485                 # One of the read calls had an issue. Just to be safe, request that the client
00486                 # reinitialize their topics.
00487                 self.requestTopics()
00488 
00489     def setPublishSize(self, bytes):
00490         if self.buffer_out < 0:
00491             self.buffer_out = bytes
00492             rospy.loginfo("Note: publish buffer size is %d bytes" % self.buffer_out)
00493 
00494     def setSubscribeSize(self, bytes):
00495         if self.buffer_in < 0:
00496             self.buffer_in = bytes
00497             rospy.loginfo("Note: subscribe buffer size is %d bytes" % self.buffer_in)
00498 
00499     def setupPublisher(self, data):
00500         """ Register a new publisher. """
00501         try:
00502             msg = TopicInfo()
00503             msg.deserialize(data)
00504             pub = Publisher(msg)
00505             self.publishers[msg.topic_id] = pub
00506             self.callbacks[msg.topic_id] = pub.handlePacket
00507             self.setPublishSize(msg.buffer_size)
00508             rospy.loginfo("Setup publisher on %s [%s]" % (msg.topic_name, msg.message_type) )
00509         except Exception as e:
00510             rospy.logerr("Creation of publisher failed: %s", e)
00511 
00512     def setupSubscriber(self, data):
00513         """ Register a new subscriber. """
00514         try:
00515             msg = TopicInfo()
00516             msg.deserialize(data)
00517             if not msg.topic_name in self.subscribers.keys():
00518                 sub = Subscriber(msg, self) 
00519                 self.subscribers[msg.topic_name] = sub
00520                 self.setSubscribeSize(msg.buffer_size)
00521                 rospy.loginfo("Setup subscriber on %s [%s]" % (msg.topic_name, msg.message_type) )
00522             elif msg.message_type != self.subscribers[msg.topic_name].message._type:
00523                 old_message_type = self.subscribers[msg.topic_name].message._type
00524                 self.subscribers[msg.topic_name].unregister()
00525                 sub = Subscriber(msg, self) 
00526                 self.subscribers[msg.topic_name] = sub
00527                 self.setSubscribeSize(msg.buffer_size)
00528                 rospy.loginfo("Change the message type of subscriber on %s from [%s] to [%s]" % (msg.topic_name, old_message_type, msg.message_type) )
00529         except Exception as e:
00530             rospy.logerr("Creation of subscriber failed: %s", e)
00531 
00532     def setupServiceServerPublisher(self, data):
00533         """ Register a new service server. """
00534         try:
00535             msg = TopicInfo()
00536             msg.deserialize(data)
00537             self.setPublishSize(msg.buffer_size)
00538             try:
00539                 srv = self.services[msg.topic_name]
00540             except:
00541                 srv = ServiceServer(msg, self)
00542                 rospy.loginfo("Setup service server on %s [%s]" % (msg.topic_name, msg.message_type) )
00543                 self.services[msg.topic_name] = srv
00544             if srv.mres._md5sum == msg.md5sum:
00545                 self.callbacks[msg.topic_id] = srv.handlePacket
00546             else:
00547                 raise Exception('Checksum does not match: ' + srv.mres._md5sum + ',' + msg.md5sum)
00548         except Exception as e:
00549             rospy.logerr("Creation of service server failed: %s", e)
00550     def setupServiceServerSubscriber(self, data):
00551         """ Register a new service server. """
00552         try:
00553             msg = TopicInfo()
00554             msg.deserialize(data)
00555             self.setSubscribeSize(msg.buffer_size)
00556             try:
00557                 srv = self.services[msg.topic_name]
00558             except:
00559                 srv = ServiceServer(msg, self)
00560                 rospy.loginfo("Setup service server on %s [%s]" % (msg.topic_name, msg.message_type) )
00561                 self.services[msg.topic_name] = srv
00562             if srv.mreq._md5sum == msg.md5sum:
00563                 srv.id = msg.topic_id
00564             else:
00565                 raise Exception('Checksum does not match: ' + srv.mreq._md5sum + ',' + msg.md5sum)
00566         except Exception as e:
00567             rospy.logerr("Creation of service server failed: %s", e)
00568 
00569     def setupServiceClientPublisher(self, data):
00570         """ Register a new service client. """
00571         try:
00572             msg = TopicInfo()
00573             msg.deserialize(data)
00574             self.setPublishSize(msg.buffer_size)
00575             try:
00576                 srv = self.services[msg.topic_name]
00577             except:
00578                 srv = ServiceClient(msg, self)
00579                 rospy.loginfo("Setup service client on %s [%s]" % (msg.topic_name, msg.message_type) )
00580                 self.services[msg.topic_name] = srv
00581             if srv.mreq._md5sum == msg.md5sum:
00582                 self.callbacks[msg.topic_id] = srv.handlePacket
00583             else:
00584                 raise Exception('Checksum does not match: ' + srv.mreq._md5sum + ',' + msg.md5sum)
00585         except Exception as e:
00586             rospy.logerr("Creation of service client failed: %s", e)
00587     def setupServiceClientSubscriber(self, data):
00588         """ Register a new service client. """
00589         try:
00590             msg = TopicInfo()
00591             msg.deserialize(data)
00592             self.setSubscribeSize(msg.buffer_size)
00593             try:
00594                 srv = self.services[msg.topic_name]
00595             except:
00596                 srv = ServiceClient(msg, self)
00597                 rospy.loginfo("Setup service client on %s [%s]" % (msg.topic_name, msg.message_type) )
00598                 self.services[msg.topic_name] = srv
00599             if srv.mres._md5sum == msg.md5sum:
00600                 srv.id = msg.topic_id
00601             else:
00602                 raise Exception('Checksum does not match: ' + srv.mres._md5sum + ',' + msg.md5sum)
00603         except Exception as e:
00604             rospy.logerr("Creation of service client failed: %s", e)
00605 
00606     def handleTimeRequest(self, data):
00607         """ Respond to device with system time. """
00608         t = Time()
00609         t.data = rospy.Time.now()
00610         data_buffer = StringIO.StringIO()
00611         t.serialize(data_buffer)
00612         self.send( TopicInfo.ID_TIME, data_buffer.getvalue() )
00613         self.lastsync = rospy.Time.now()
00614         
00615 
00616     def handleParameterRequest(self, data):
00617         """ Send parameters to device. Supports only simple datatypes and arrays of such. """
00618         req = RequestParamRequest()
00619         req.deserialize(data)
00620         resp = RequestParamResponse()
00621         try:
00622             param = rospy.get_param(req.name)
00623         except KeyError:
00624             rospy.logerr("Parameter %s does not exist"%req.name)
00625             return
00626 
00627         if param == None:
00628             rospy.logerr("Parameter %s does not exist"%req.name)
00629             return
00630 
00631         if (type(param) == dict):
00632             rospy.logerr("Cannot send param %s because it is a dictionary"%req.name)
00633             return
00634         if (type(param) != list):
00635             param = [param]
00636         #check to make sure that all parameters in list are same type
00637         t = type(param[0])
00638         for p in param:
00639             if t!= type(p):
00640                 rospy.logerr('All Paramers in the list %s must be of the same type'%req.name)
00641                 return
00642         if (t == int):
00643             resp.ints= param
00644         if (t == float):
00645             resp.floats=param
00646         if (t == str):
00647             resp.strings = param
00648         data_buffer = StringIO.StringIO()
00649         resp.serialize(data_buffer)
00650         self.send(TopicInfo.ID_PARAMETER_REQUEST, data_buffer.getvalue())
00651 
00652     def handleLoggingRequest(self, data):
00653         """ Forward logging information from serial device into ROS. """
00654         msg = Log()
00655         msg.deserialize(data)
00656         if (msg.level == Log.ROSDEBUG):
00657             rospy.logdebug(msg.msg)
00658         elif(msg.level== Log.INFO):
00659             rospy.loginfo(msg.msg)
00660         elif(msg.level== Log.WARN):
00661             rospy.logwarn(msg.msg)
00662         elif(msg.level== Log.ERROR):
00663             rospy.logerr(msg.msg)
00664         elif(msg.level==Log.FATAL):
00665             rospy.logfatal(msg.msg)
00666 
00667     def send(self, topic, msg):
00668         """ Send a message on a particular topic to the device. """
00669         with self.mutex:
00670             length = len(msg)
00671             if self.buffer_in > 0 and length > self.buffer_in:
00672                 rospy.logerr("Message from ROS network dropped: message larger than buffer.")
00673                 print msg
00674                 return -1
00675             else:
00676                     #modified frame : header(2 bytes) + msg_len(2 bytes) + msg_len_chk(1 byte) + topic_id(2 bytes) + msg(x bytes) + msg_topic_id_chk(1 byte)
00677                     # second byte of header is protocol version
00678                     msg_len_checksum = 255 - ( ((length&255) + (length>>8))%256 )
00679                     msg_checksum = 255 - ( ((topic&255) + (topic>>8) + sum([ord(x) for x in msg]))%256 )
00680                     data = "\xff" + self.protocol_ver  + chr(length&255) + chr(length>>8) + chr(msg_len_checksum) + chr(topic&255) + chr(topic>>8)
00681                     data = data + msg + chr(msg_checksum)
00682                     self.port.write(data)
00683                     return length
00684 
00685     def sendDiagnostics(self, level, msg_text):
00686         msg = diagnostic_msgs.msg.DiagnosticArray()
00687         status = diagnostic_msgs.msg.DiagnosticStatus()
00688         status.name = "rosserial_python"
00689         msg.header.stamp = rospy.Time.now()
00690         msg.status.append(status)
00691 
00692         status.message = msg_text
00693         status.level = level
00694 
00695         status.values.append(diagnostic_msgs.msg.KeyValue())
00696         status.values[0].key="last sync"
00697         if self.lastsync.to_sec()>0:
00698             status.values[0].value=time.ctime(self.lastsync.to_sec())
00699         else:
00700             status.values[0].value="never"
00701 
00702         status.values.append(diagnostic_msgs.msg.KeyValue())
00703         status.values[1].key="last sync lost"
00704         status.values[1].value=time.ctime(self.lastsync_lost.to_sec())
00705 
00706         self.pub_diagnostics.publish(msg)
00707 


rosserial_python
Author(s): Michael Ferguson
autogenerated on Fri Aug 28 2015 12:44:45