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


rosserial_python
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 19:56:30