rocon_iot_bridge.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_devices/license/LICENSE
00005 #
00006 
00007 import copy
00008 import rospy
00009 import requests
00010 import threading
00011 import rocon_device_msgs.srv as rocon_device_srvs
00012 import rocon_device_msgs.msg as rocon_device_msgs
00013 
00014 from flask import Flask
00015 from flask import request
00016 
00017 class RoconIOTBridge(object):
00018     def __init__(self, local_address, local_port, global_address, global_port, connector):
00019         self._app = Flask(rospy.get_name())
00020         self._local_address = local_address
00021         self._local_port = local_port
00022         self._global_address = global_address
00023         self._global_port = global_port
00024         self._connector = connector
00025 
00026         self._device_event = rocon_device_msgs.Devices()
00027         self._is_device_event_ready = False
00028         self._lock = threading.Lock()
00029 
00030 
00031     def _init_flask(self):
00032         self._app.add_url_rule('/ping', view_func=self._pong, methods=['GET'])
00033         self._app.add_url_rule('/devices', view_func=self._received_devices_event, methods=['POST'])
00034         self._app.add_url_rule(rule='/shutdown', view_func=self._shutdown_flask)
00035 
00036         self._server_thread = threading.Thread(target=self._app.run, kwargs={'host': self._local_address, 'port': self._local_port, 'debug': False}) 
00037 
00038     def _init_ros_api(self):
00039         self._srv_get_device_list = rospy.Service('get_device_list', rocon_device_srvs.GetDeviceList, self._process_get_device_list)
00040         self._pub_device_event = rospy.Publisher('devices', rocon_device_msgs.Devices, queue_size=10)
00041 
00042     def spin(self):
00043         self._init_flask()
00044         self._init_ros_api()
00045 
00046         subscription_uri = "%s:%s/devices"%(self._global_address, self._global_port)
00047         self.loginfo("initialising with %s"%subscription_uri)
00048         resp, message = self._connector.init({"address": self._global_address, "port": self._global_port, "api":"devices"})
00049         if resp:
00050             self.loginfo(str(resp))
00051         else:
00052             self.logerr(message)
00053             return
00054 
00055         self.loginfo("Starting bridge server...")
00056         self._server_thread.start()
00057         self.loginfo("Started...")
00058 
00059         while not rospy.is_shutdown():
00060             rospy.sleep(1.0)
00061 
00062         resp = self._connector.close()
00063         if resp:
00064             self.loginfo(str(resp))
00065         result, e = self._shutdown_server()
00066         self.loginfo(e)
00067         self._server_thread.join(1)
00068 
00069     def _received_devices_event(self):
00070         req = request.json
00071         self.loginfo("Received : %s"%str(req))
00072         msg = self._connector.convert_post_to_devices_msg(req)
00073         self._pub_device_event.publish(msg)
00074         return 'Success'
00075 
00076     def _process_get_device_list(self, req):
00077         devices = self._connector.call_get_device_list()
00078         return rocon_device_srvs.GetDeviceListResponse(devices)
00079 
00080     def _pong(self):
00081         self.loginfo("pong!")
00082         return "pong!"
00083 
00084     def _shutdown_flask(self, methods=['GET']):
00085         self.loginfo('shutdown requested')
00086         func = request.environ.get('werkzeug.server.shutdown')
00087         if func is None:
00088             raise RuntimeError('Not running with the Werkzeug Server')
00089         func()
00090 
00091     def _shutdown_server(self):
00092         try:
00093             address = 'http://' + self._local_address + ':' + str(self._local_port) + '/shutdown'
00094             resp = requests.get(address)
00095         except Exception, e:
00096             return (False, e)
00097         else:
00098             return (True, 'server shutdown success!!')
00099 
00100     def loginfo(self, msg):
00101         rospy.loginfo("%s : %s"%(rospy.get_name(), msg))
00102 
00103     def logerr(self, msg):
00104         rospy.logerr("%s : %s"%(rospy.get_name(), msg))


rocon_iot_bridge
Author(s): Dongwook Lee, Jihoon Lee
autogenerated on Thu Jun 6 2019 17:58:46