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


rosserial_python
Author(s): Michael Ferguson
autogenerated on Sat Oct 7 2017 03:08:48