environment_sensor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 
00005 import rospy
00006 from docomo_perception.srv import (EnvironmentSensorService, EnvironmentSensorServiceResponse)
00007 from docomo_perception.msg import EnvironmentSensor
00008 
00009 import json
00010 import requests
00011 import yaml
00012 import copy
00013 import threading
00014 
00015 global APIHOST, APIKEY, LONGTITUDE, LATITUDE, RANGE
00016 setting_path = "/var/lib/robot/docomo_environment_sensor_settings.yaml"
00017 
00018 
00019 class DocomoEnvironmentSensoeNode(object):
00020     def __init__(self):
00021         self.srv = rospy.Service("environment_sensor", EnvironmentSensorService, self.serviceCallback)
00022         self.lock = threading.Lock()
00023 
00024     def serviceCallback(self, req):
00025         params = {
00026             "APIKEY": APIKEY,
00027             "with_data": "true",
00028             "order": "prefecture,asc,city,asc"
00029             }
00030         if req.base_id and len(req.base_id) > 0 and req.base_id[0] != "":
00031             params["id"] = req.base_id
00032         else:
00033             if req.latitude:
00034                 params["lat"] = str(req.latitude)
00035             else:
00036                 params["lat"] = LATITUDE
00037             if req.longtitude:
00038                 params["lon"] = str(req.longtitude)
00039             else:
00040                 params["lon"] = LONGTITUDE
00041             if req.range:
00042                 params["range"] = str(req.range)
00043             elif RANGE:
00044                 params["range"] = RANGE
00045 
00046         envlist = []
00047         for data_type in ["1013", "1213", "2221"]:
00048             p = copy.deepcopy(params)
00049             p["data_type"] = data_type
00050             self.lock.acquire()
00051             rospy.loginfo("param: %s", p)
00052             urlres = requests.get(APIHOST, params=p)
00053             self.lock.release()
00054             rospy.loginfo("sent request to %s -> %d", urlres.url, urlres.status_code)
00055             rospy.loginfo("content: %s", urlres.content)
00056             if urlres.status_code is not requests.codes.ok:
00057                 rospy.logerr("bad status code: %d", urlres.status_code)
00058                 return EnvironmentSensorServiceResponse()
00059             resdic = json.loads(urlres.content)
00060 
00061             for s in resdic["sensor"]:
00062                 try:
00063                     idx = [e.base_id for e in envlist].index(s["id"])
00064                     env_data = s["environment_data"][0]
00065                     dt = int(env_data["data_type"])
00066                     val = float(env_data["val"][0])
00067                     rospy.logwarn("val2: %f", val)
00068                     if dt == 1013:
00069                         envlist[idx].temperature = val
00070                     elif dt == 1213:
00071                         envlist[idx].precipitation = val
00072                     elif dt == 2221:
00073                         envlist[idx].uv_index = val
00074                     else:
00075                         rospy.logwarn("received invalid data_type: %s", env_data["data_type"])
00076                 except:
00077                     sensor_msg = EnvironmentSensor()
00078                     sensor_msg.base_id = s["id"]
00079                     sensor_msg.name = s["name"]
00080                     sensor_msg.prefecture = s["prefecture"]
00081                     sensor_msg.city = s["city"]
00082                     sensor_msg.latitude = float(s["lat"])
00083                     sensor_msg.longtitude = float(s["lon"])
00084                     env_data = s["environment_data"][0]
00085                     dt = int(env_data["data_type"])
00086                     val = float(env_data["val"][0])
00087                     if dt == 1013:
00088                         sensor_msg.temperature = val
00089                     elif dt == 1213:
00090                         sensor_msg.precipitation = val
00091                     elif dt == 2221:
00092                         sensor_msg.uv_index = val
00093                     else:
00094                         rospy.logwarn("received invalid data_type: %s", env_data["data_type"])
00095                     envlist.append(sensor_msg)
00096         res = EnvironmentSensorServiceResponse()
00097         res.data = envlist
00098         return res
00099 
00100 def load_environment_sensor_settings():
00101     global APIHOST, APIKEY, LONGTITUDE, LATITUDE, RANGE
00102 
00103     try:
00104         with open(setting_path) as f:
00105             key = yaml.load(f)
00106             APIHOST = key['APIHOST']
00107             APIKEY = key['APIKEY']
00108             if key.has_key("LONGTITUDE"):
00109                 LONGTITUDE = key["LONGTITUDE"]
00110             if key.has_key("LATITUDE"):
00111                 LATITUDE = key["LATITUDE"]
00112             if key.has_key("RANGE"):
00113                 RANGE = key["RANGE"]
00114             rospy.loginfo("loaded settings")
00115     except IOError as e:
00116         rospy.logerr('"%s" not found : %s' % (settings_path, e))
00117         exit(-1)
00118     except Exception as e:
00119         rospy.logerr("failed to load settings: %s", e)
00120         rospy.logerr("check if exists valid setting file in %s", settings_path)
00121         exit(-1)
00122 
00123 
00124 if __name__ == '__main__':
00125     rospy.init_node("docomo_environment_sensor_node")
00126     n = DocomoEnvironmentSensoeNode()
00127     load_environment_sensor_settings()
00128     rospy.spin()


docomo_perception
Author(s): Yuki Furuta
autogenerated on Thu Jun 6 2019 18:03:42