smartthings_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 
00008 import json
00009 import requests
00010 import rospy
00011 import rocon_std_msgs.msg as rocon_std_msgs
00012 import rocon_device_msgs.msg as rocon_device_msgs
00013 from rocon_iot_bridge import RoconIOTBridge, Connector
00014 
00015 class SmartThingsConnector(Connector):
00016 
00017     _API = {
00018         'UPDATE_CONFIG' : 'configuration',
00019         'GET_DEVICE_LIST' : 'get_device_list',
00020         'LOG':  'log',
00021         'RESET': 'reset'
00022     }
00023 
00024     def __init__(self):
00025         self._configuration_file = rospy.get_param('~target_configuration_file')
00026 
00027     def _load_configuration(self, filename):
00028         with open(filename) as f:
00029             config = json.load(f) 
00030         self._config = config
00031 
00032         if not 'access_token' in self._config:
00033             return False
00034         else:
00035             return True
00036 
00037     def init(self, config=None):
00038 
00039         if not self._load_configuration(self._configuration_file):
00040             return None, "Error while loading configuration : %s"%self._config
00041 
00042         self._endpoint_url = self._get_endpoint_url()
00043 
00044         if config:
00045             return self.request_configuration_update(config), "Success"
00046         else:
00047             return None, "No configuration is given"
00048 
00049     def close(self):
00050         return self._request_reset()
00051 
00052     def call_get_device_list(self):
00053         request_url = "%s/%s"%(self._endpoint_url, self._API['GET_DEVICE_LIST'])
00054         params = {}
00055         header =  {
00056           "Authorization": "Bearer %s" % self._config['access_token'],
00057         }
00058         resp = requests.get(url=request_url, params=params, headers=header)
00059         dev_resp = resp.json()
00060 
00061         devices = []
00062         for dev_type, devs in dev_resp.items():
00063             if devs:
00064                 for d in devs:
00065                     dev_msg = self._convert_to_device_msg(dev_type, d)
00066                     devices.append(dev_msg)
00067         return devices
00068 
00069     def _convert_to_device_msg(self, d_type, d):
00070         m = rocon_device_msgs.Device()
00071         m.label = str(d['label'])
00072         m.uuid  = str(d['id'])
00073         m.type  = str(d_type)
00074         m.data  = []
00075 
00076         return m
00077 
00078 
00079     def _request_reset(self):
00080         request_url = "%s/%s"%(self._endpoint_url, self._API['RESET'])
00081         params = {}
00082         header =  {
00083           "Authorization": "Bearer %s" % self._config['access_token'],
00084         }
00085         resp = requests.put(url=request_url, params={}, headers=header)
00086         # Return true or false
00087         return resp
00088 
00089     def request_configuration_update(self, config):
00090         request_url = "%s/%s"%(self._endpoint_url, self._API['UPDATE_CONFIG'])
00091         header = { "Authorization": "Bearer %s" % self._config['access_token'],}
00092         resp = requests.put(url=request_url, params=config, headers=header)
00093         
00094         # Return true or false
00095         return resp
00096 
00097     def convert_post_to_devices_msg(self, post):
00098         device = post['topic']
00099         device_data = post['data']
00100         dev_label, dev_type, dev_uuid = device.split("/")
00101 
00102         dev = rocon_device_msgs.Device()
00103         dev.label = str(dev_label)
00104         dev.type  = str(dev_type)
00105         dev.uuid  = str(dev_uuid)
00106         dev.data  = [rocon_std_msgs.KeyValue(str(key), str(value)) for key, value in device_data.items()]
00107 
00108         msg = rocon_device_msgs.Devices()
00109         msg.devices = []
00110         msg.devices.append(dev)
00111 
00112         return msg
00113 
00114     def _get_endpoint_url(self):
00115         endpoints_url = self._config['api']
00116         endpoints_paramd = {
00117             "access_token": self._config['access_token']
00118         }
00119 
00120         endpoints_response = requests.get(url=endpoints_url, params=endpoints_paramd)
00121         end_url = endpoints_response.json()[0]['url']
00122         endpoint_url = 'http://%s%s'%(self._config['api_location'], end_url)
00123 
00124         return endpoint_url
00125 
00126 
00127 if __name__ == '__main__':
00128     rospy.init_node('smartthings_bridge')
00129     
00130     local_address = rospy.get_param('~local_address')
00131     local_port    = rospy.get_param('~local_port')
00132     global_address = rospy.get_param('~global_address')
00133     global_port    = rospy.get_param('~global_port')
00134 
00135     connector = SmartThingsConnector()
00136     bridge = RoconIOTBridge(local_address, local_port, global_address, global_port, connector)
00137 
00138     bridge.loginfo("Initilialised")
00139     bridge.spin()
00140     bridge.loginfo("Bye Bye")


rocon_smartthings_bridge
Author(s): Jihoon Lee
autogenerated on Thu Jun 6 2019 17:58:53