test_non-ros_service_server_complex-srv.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 import sys
00003 import socket
00004 import time
00005 from random import randint
00006 try:
00007     import ujson as json
00008 except ImportError:
00009     try:
00010         import simplejson as json
00011     except ImportError:
00012         import json
00013 
00014 
00015 ####################### variables begin ########################################
00016 # these parameters should be changed to match the actual environment           #
00017 ################################################################################
00018 
00019 tcp_socket_timeout = 10                          # seconds
00020 max_msg_length = 20000                           # bytes
00021 
00022 rosbridge_ip = "localhost"                       # hostname or ip
00023 rosbridge_port = 9090                            # port as integer
00024 
00025 service_module = "rosbridge_library"         # make sure srv and msg files are available within specified module on rosbridge-server!
00026 service_type = "TestNestedService"           # make sure this matches an existing service type on rosbridge-server (in specified srv_module)
00027 service_name = "nested_srv"                      # service name
00028 
00029 send_fragment_size = 1000
00030 # delay between sends to rosbridge is not needed anymore, if using my version of protocol (uses buffer to collect data from stream)
00031 send_fragment_delay = 0.000#1
00032 receive_fragment_size = 10
00033 receive_message_intervall = 0.0
00034 
00035 ####################### variables end ##########################################
00036 
00037 
00038 ####################### service_calculation begin ##############################
00039 # change this function to match whatever service should be provided            #
00040 ################################################################################
00041 
00042 def calculate_service_response(request):
00043     request_object = json.loads(request)                                        # parse string for service request
00044     args = request_object["args"]                                               # get parameter field (args)
00045 #    count = int(args["count"] )                                                 # get parameter(s) as described in corresponding ROS srv-file
00046 #
00047 #    message = ""                                                                # calculate service response
00048 #    for i in range(0,count):
00049 #        message += str(chr(randint(32,126)))
00050 #        if i% 100000 == 0:
00051 #            print count - i, "bytes left to generate"
00052 
00053     message = {"data": {"data": 42.0}}
00054     
00055     """
00056     IMPORTANT!
00057     use base64 encoding to avoid JSON-parsing problems!
00058     --> use .decode("base64","strict") at client side
00059     """
00060     #message = message.encode('base64','strict')
00061     service_response_data = message                                   # service response (as defined in srv-file)
00062 
00063     response_object = { "op": "service_response",
00064                         "request_id": request_object["request_id"],
00065                         "data": service_response_data                           # put service response in "data"-field of response object (in this case it's twice "data", because response value is also named data (in srv-file)
00066                       }
00067     response_message = json.dumps(response_object)
00068     return response_message
00069 
00070 ####################### service_calculation end ################################
00071 
00072 
00073 
00074 ####################### helper functions / and variables begin #################
00075 # should not need to be changed (but could be improved )                       #
00076 ################################################################################
00077 
00078 buffer = ""
00079 
00080 def connect_tcp_socket():
00081     tcp_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)                # connect to rosbridge
00082     tcp_sock.settimeout(tcp_socket_timeout)
00083     tcp_sock.connect((rosbridge_ip, rosbridge_port))
00084     return tcp_sock
00085 
00086 def advertise_service():                                                        # advertise service
00087     advertise_message_object = {"op":"advertise_service",                       
00088                                 "service_module": service_module,
00089                                 "service_type": service_type,
00090                                 "service_name": service_name,
00091                                 "fragment_size": receive_fragment_size,
00092                                 "message_intervall": receive_message_intervall
00093                                 }
00094     advertise_message = json.dumps(advertise_message_object)                    
00095     tcp_socket.send(str(advertise_message))
00096 
00097 def unadvertise_service():                                                      # unadvertise service
00098     unadvertise_message_object = {"op":"stop_service",                           
00099                                   "service_name": service_name
00100                                  }
00101     unadvertise_message = json.dumps(unadvertise_message_object)                   
00102     tcp_socket.send(str(unadvertise_message))
00103 
00104 def wait_for_service_request():                                                 # receive data from rosbridge
00105     data = None
00106     global buffer
00107 
00108     try:
00109         done = False
00110         global buffer
00111         while not done:
00112             incoming = tcp_socket.recv(max_msg_length)                          # get data from socket
00113             if incoming == '':
00114                 print "connection closed by peer"
00115                 sys.exit(1)
00116             buffer = buffer + incoming                                          # append data to buffer
00117             try:                                                                # try to parse JSON from buffer
00118                 data_object = json.loads(buffer)
00119                 if data_object["op"] == "service_request":
00120                     data = buffer
00121                     done = True
00122                     return data                                                 # if parsing was successful --> return data string
00123             except Exception, e:
00124                 #print "direct_access error:"
00125                 #print e
00126                 pass
00127                
00128             #print "trying to defragment"
00129             try:                                                                # opcode was not "service_request" -> try to defragment
00130                 result_string = buffer.split("}{")                              # split buffer into fragments and re-fill with curly brackets
00131                 result = []
00132                 for fragment in result_string:
00133                     if fragment[0] != "{":
00134                         fragment = "{"+fragment
00135                     if fragment[len(fragment)-1] != "}":
00136                         fragment = fragment + "}"
00137                     result.append(json.loads(fragment))
00138 
00139                 try:                                                            # try to defragment when received all fragments
00140                     fragment_count = len(result)
00141                     announced = int(result[0]["total"])
00142 
00143                     if fragment_count == announced:
00144                         reconstructed = ""
00145                         sorted_result = [None] * fragment_count                 # sort fragments..
00146                         unsorted_result = []
00147                         for fragment in result:
00148                             unsorted_result.append(fragment)
00149                             sorted_result[int(fragment["num"])] = fragment
00150 
00151                         for fragment in sorted_result:                          # reconstruct from fragments
00152                             reconstructed = reconstructed + fragment["data"]
00153 
00154                         #print "reconstructed", reconstructed
00155                         buffer = ""                                             # empty buffer
00156                         done = True
00157                         print "reconstructed message from", len(result), "fragments"
00158                         #print reconstructed
00159                         return reconstructed
00160                 except Exception, e:
00161                     print "not possible to defragment:", buffer
00162                     print e
00163             except Exception, e:
00164                 print "defrag_error:", buffer
00165                 print e
00166                 pass
00167     except Exception, e:
00168         #print "network-error(?):", e
00169         pass
00170     return data
00171 
00172 def send_service_response(response):                                            # send response to rosbridge
00173     tcp_socket.send(response)
00174 
00175 def list_of_fragments(full_message, fragment_size):                             # create fragment messages for a huge message
00176     message_id = randint(0,64000)                                               # generate random message id
00177     fragments = []                                                              # generate list of data fragments
00178     cursor = 0
00179     while cursor < len(full_message):
00180         fragment_begin = cursor
00181         if len(full_message) < cursor + fragment_size:
00182             fragment_end = len(full_message)
00183             cursor = len(full_message)
00184         else:
00185             fragment_end = cursor + fragment_size
00186             cursor += fragment_size
00187         fragment = full_message[fragment_begin:fragment_end]
00188         fragments.append(fragment)
00189 
00190     fragmented_messages_list = []                                               # generate list of fragmented messages (including headers)
00191     if len(fragments) > 1:
00192         for count, fragment in enumerate(fragments):                            # iterate through list and have index counter
00193             fragmented_message_object = {"op":"fragment",                       #   create python-object for each fragment message
00194                                          "id": str(message_id),
00195                                          "data": str(fragment),
00196                                          "num": count,
00197                                          "total": len(fragments)
00198                                          }
00199             fragmented_message = json.dumps(fragmented_message_object)          # create JSON-object from python-object for each fragment message
00200             fragmented_messages_list.append(fragmented_message)                 # append JSON-object to list of fragmented messages
00201     else:                                                                       # if only 1 fragment --> do not send as fragment, but as service_response
00202         fragmented_messages_list.append(str(fragment))
00203     return fragmented_messages_list                                             # return list of 'ready-to-send' fragmented messages
00204 
00205 ####################### helper functions end ###################################
00206 
00207 
00208 ####################### script begin ###########################################
00209 # should not need to be changed (but could be improved )                       #
00210 ################################################################################
00211 
00212 tcp_socket = connect_tcp_socket()                                               # open tcp_socket
00213 advertise_service()                                                             # advertise service in ROS (via rosbridge)
00214 print "service provider started and waiting for requests"
00215 
00216 try:                                                                            # allows to catch KeyboardInterrupt
00217     while True:                                                                 # loop forever (or until ctrl-c is pressed)
00218         data = None
00219         try:                                                                    # allows to catch any Exception (network, json, ..)
00220           data = wait_for_service_request()                                     # receive request from rosbridge
00221           if data == '':                                                        # exit on empty string
00222               break                                                             
00223           elif data != None and len(data) > 0:                                  # received service_request (or at least some data..)
00224             response = calculate_service_response(data)                         # generate service_response
00225 
00226             print "response calculated, now splitting into fragments.."
00227             fragment_list = list_of_fragments(response, send_fragment_size)     # generate fragments to send to rosbridge
00228 
00229             print "sending", len(fragment_list), "messages as response"
00230             for fragment in fragment_list:
00231                 #print "sending:" ,fragment
00232                 send_service_response(fragment)                                 # send service_response to rosbridge (or fragments; just send any list entry)
00233                 time.sleep(send_fragment_delay)                                 # (not needed if using patched rosbridge protocol.py)
00234         except Exception, e:
00235           print e
00236           pass
00237 except KeyboardInterrupt:
00238     try:
00239         unadvertise_service()                                                   # unadvertise service
00240         tcp_socket.close()                                                      # close tcp_socket
00241     except Exception, e:
00242         print e
00243     print "non-ros_service_server stopped because user pressed \"Ctrl-C\""


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Mon Oct 6 2014 06:58:09