Skip to content

Commit

Permalink
mount: position feedback based on HBSTEP counter, clean code, better …
Browse files Browse the repository at this point in the history
…HBSTEP setting, modify RUN function of HBSTEP, right tracking speed, software for mount calibration (1 revolution steps counter), new AWS weatheunderground methods (real time upload)
  • Loading branch information
roman-dvorak committed Jan 30, 2017
1 parent c8116e3 commit 53e0148
Show file tree
Hide file tree
Showing 6 changed files with 450 additions and 35 deletions.
60 changes: 60 additions & 0 deletions src/arom_manager.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
#!/usr/bin/env python
# -*- coding: utf-8 -*-

import math
import time
import rospy
import std_msgs
import json
import os
from std_msgs.msg import String
from std_msgs.msg import Float32
from arom.srv import *
from arom.msg import *
import numpy as np
import pylirc
from drivers.__init__ import AromNode

try:
import xml.etree.cElementTree as ET
except ImportError:
import xml.etree.ElementTree as ET

recieved = []

def manager_callback(recive):
global recieved
recieved.append(recive.data)
#print recive, recieved

class arom_manager(AromNode):
node_name = "arom_manager"
node_type = "arom_manager"
node_pymlab = True

def __init__(self, rows = 2, cols = 2, file = None):
print os.path.abspath(__file__)

rospy.Subscriber("/arom/manager", std_msgs.msg.String, manager_callback)

AromNode.__init__(self)
self.set_feature('arom_nodes',{'publish': '/arom/manager'})

##
## Konec zakladni inicializace
##

rate = rospy.Rate(10)
while not rospy.is_shutdown():
try:
if len(recieved) > 0:
print recieved
except Exception, e:
print e
time.sleep(0.5)




if __name__ == '__main__':
m = arom_manager()
3 changes: 2 additions & 1 deletion src/drivers/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,4 +25,5 @@ def pymlab(self, *args, **kwds):
self.pymlabService(**kwds)

def set_feature(self, name, value):
rospy.set_param('/arom/node'+ str(rospy.get_name()) + '/feature/'+name, value)
rospy.set_param('/arom/node%s/feature/%s' %(str(rospy.get_name()),name), value)
rospy.loginfo("New feature '%s' for %s" %(rospy.get_name(), name))
208 changes: 183 additions & 25 deletions src/drivers/aws_weatherunderground.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,46 +5,204 @@
import rospy
from arom.srv import *
from arom.msg import *
from std_msgs.msg import String
import httplib2

from __init__ import AromNode

data = {}

def callback(recive):
global data
for i, type in enumerate(recive.type):
data[type] = recive.value[i]
print data
#print data

def update_parameters(recive):
data = eval(recive.data)
print '/arom/node%s/feature/aws_uploader_api_params/data/%s/%s/' %(rospy.get_name(), data['id'], 'value')
rospy.set_param('/arom/node%s/feature/aws_uploader_api_params/data/%s/%s/' %(rospy.get_name(), data['id'], 'value'), data['source'])

def weatherUploader():
name = 'aws_weatherudnerground'
rospy.init_node(name, anonymous=True)
rospy.Subscriber("/aws_out", msg_WeatherStation, callback)
class weatherUploader(AromNode):
node_name = "aws_weatherudnerground"
node_type = "aws_uploader"
node_pymlab = False

ID = rospy.get_param('/arom/aws/%s/ID'%(name))
PASSWORD = rospy.get_param('/arom/aws/%s/PASSWORD'%(name))
def __init__(self):
rospy.Subscriber("/aws_out", msg_WeatherStation, callback)
rospy.Subscriber("/%s/update_parameters"%(self.node_name), String, update_parameters)
ID = rospy.get_param('/arom/aws/%s/ID'%(self.node_name))
PASSWORD = rospy.get_param('/arom/aws/%s/PASSWORD'%(self.node_name))

AromNode.__init__(self)
self.UpdateFeature()

rate = rospy.Rate(0.2) # 10hz
while data == {} and not rospy.is_shutdown():
time.sleep(0.25)
while not rospy.is_shutdown():
try:
print "Ahoj :)"
self.UpdateFeature()
req = ""
types = rospy.get_param('/arom/node/aws_weatherudnerground/feature/aws_uploader_api_params/data/')
for preset in self.aws_preset:
try:
req += "&%s=%s" %(str(self.aws_preset[preset]), preset)

except Exception, e:
rospy.loginfo("#1> " + repr(e))

for sensor in data:
try:
print
req += "&%s=%f" %(self.aws_data[sensor], self.ConvertValue(float(data[sensor]), self.api_data[self.aws_data[sensor]]['unit']))

except Exception, e:
rospy.loginfo("#2> " + repr(e))

print req

print "https://rtupdate.wunderground.com/weatherstation/updateweatherstation.php?realtime=1&rtfreq=5"+req

#resp, content = httplib2.Http().request("http://weatherstation.wunderground.com/weatherstation/updateweatherstation.php"+req)
resp, content = httplib2.Http().request("https://rtupdate.wunderground.com/weatherstation/updateweatherstation.php?realtime=1&rtfreq=5"+req)
except Exception, e:
rospy.logerr(e)

rate.sleep()

def ConvertValue(self, value, outUnit, multiply = 1):
if outUnit == 'fahrenheit':
print "CALC FAHRENHEIT"
calc = value * 9/5 + 32
else:
print "NO CALC"
calc = value

return calc*multiply



def UpdateFeature(self):
self.aws_data = {}
self.aws_preset={}
self.api_data = rospy.get_param('/arom/node%s/feature/aws_uploader_api_params/data' %(str(rospy.get_name())), False)
print self.api_data
if not self.api_data:
self.api_data = {'action':{'type': 'static', 'when': 'always', 'value': 'updateraw'},
'ID': {'type': 'preset', 'when': 'always'},
'PASSWORD':{'type': 'preset', 'when': 'always'},
'softwaretype': {'type': 'static', 'when': 'always', 'value': 'AROM-Autonomou-robotic-observatory-manager'},
'dateutc': {'type': 'static', 'when': 'always', 'value': 'now'},

'winddir': {'type': 'data', 'when': '0;360', 'unit': 'degree', 'multiply': 1},
'windspeedmph': {'type': 'data', 'when': '0;200', 'unit': 'mph', 'multiply': 1},
'windgustmph': {'type': 'data', 'when': '0;200', 'unit': 'mph', 'multiply': 1},
'windgustdir': {'type': 'data', 'when': '0;360', 'unit': 'degree', 'multiply': 1},
'windspdmph_avg2m': {'type': 'data', 'when': '0;200', 'unit': 'mph', 'multiply': 1},
'winddir_avg2m': {'type': 'data', 'when': '0;360', 'unit': 'degree', 'multiply': 1},
'windgustdir_10m': {'type': 'data', 'when': '0;360', 'unit': 'degree', 'multiply': 1},
'humidity': {'type': 'data', 'when': '0;100', 'unit': 'percentage', 'multiply': 1},
'dewptf': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'tempf': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'rainin': {'type': 'data', 'when': '0;100', 'unit': 'inch', 'multiply': 1},
'dailyrainin': {'type': 'data', 'when': '0;100', 'unit': 'inch', 'multiply': 1},
'baromin': {'type': 'data', 'when': '500;1500', 'unit': 'pressure', 'multiply': 1},
'weather': {'type': 'data', 'unit': 'text', 'multiply': 1},
'clouds': {'type': 'data', 'unit': 'text', 'multiply': 1},
'soiltempf': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soiltemp2f': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soiltemp3f': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soiltemp4f': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soiltemp5f': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soilmoisture': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soilmoisture2': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soilmoisture3': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soilmoisture4': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'soilmoisture5': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
'leafwetness': {'type': 'data', 'when': '0;100', 'unit': 'percentage', 'multiply': 1},
'leafwetness2': {'type': 'data', 'when': '0;100', 'unit': 'percentage', 'multiply': 1},
'solarradiation': {'type': 'data', 'when': '0;1000', 'unit': 'wpm', 'multiply': 1},
'UV': {'type': 'data', 'when': '0;10', 'unit': 'index', 'multiply': 1},
'visibility': {'type': 'data', 'when': 'always', 'unit': 'miles', 'multiply': 1},
'indoorhumidity': {'type': 'data', 'when': '0;100', 'unit': 'percentage', 'multiply': 1},
'indoortempf': {'type': 'data', 'when': '-40;120', 'unit': 'fahrenheit', 'multiply': 1},
}
self.set_feature('aws_uploader_api_params',{'data': self.api_data})

for value in self.api_data:
if self.api_data[value]['type'] == 'data' and 'value' in self.api_data[value]:
self.aws_data[self.api_data[value]['value']] = value
elif (self.api_data[value]['type'] == 'preset' or self.api_data[value]['type'] == 'static') and 'value' in self.api_data[value]:
self.aws_preset[self.api_data[value]['value']] = value

#print "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^66"
#print self.aws_data
#print "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^66"
#print self.aws_preset

rate = rospy.Rate(0.01) # 10hz
while data == {} and not rospy.is_shutdown():
time.sleep(0.25)
while not rospy.is_shutdown():
try:
req = "?ID=%s&PASSWORD=%s&dateutc=now&softwaretype=AROM-AWS" %(ID , PASSWORD)
req += "&tempf=%f" %(data['temperatureAWS0']*9/5+32)
req += "&dewptf=%f" %(data['dewpointAWS']*9/5+32)
req += "&humidity=%f" %(data['humidityAWS0'])
req += "&winddir=%f" %(data['winddirAWS'])
req += "&windspeedmph=%f" %(data['windspdAWS'])
req += "&baromin=%f" %(data['pressureAWS']*0.0002952998751)

rospy.loginfo("Uploading data to weatherudnerground.com: %s" %repr(req))
resp, content = httplib2.Http().request("http://weatherstation.wunderground.com/weatherstation/updateweatherstation.php"+req)
except Exception, e:
rospy.logerr(e)

rate.sleep()


if __name__ == '__main__':
weatherUploader()
weatherUploader()





'''
action [action=updateraw] -- always supply this parameter to indicate you are making a weather observation upload
ID [ID as registered by wunderground.com]
PASSWORD [Station Key registered with this PWS ID, case sensitive]
dateutc - [YYYY-MM-DD HH:MM:SS (mysql format)] In Universal Coordinated Time (UTC) Not local time
=========================
winddir - [0-360 instantaneous wind direction]
windspeedmph - [mph instantaneous wind speed]
windgustmph - [mph current wind gust, using software specific time period]
windgustdir - [0-360 using software specific time period]
windspdmph_avg2m - [mph 2 minute average wind speed mph]
winddir_avg2m - [0-360 2 minute average wind direction]
windgustmph_10m - [mph past 10 minutes wind gust mph ]
windgustdir_10m - [0-360 past 10 minutes wind gust direction]
humidity - [% outdoor humidity 0-100%]
dewptf- [F outdoor dewpoint F]
tempf - [F outdoor temperature] (for extra outdoor sensors use temp2f, temp3f, and so on)
rainin - [rain inches over the past hour)] -- the accumulated rainfall in the past 60 min
dailyrainin - [rain inches so far today in local time]
baromin - [barometric pressure inches]
weather - [text] -- metar style (+RA)
clouds - [text] -- SKC, FEW, SCT, BKN, OVC
soiltempf - [F soil temperature] (for sensors 2,3,4 use soiltemp2f, soiltemp3f, and soiltemp4f)
soilmoisture - [%] (for sensors 2,3,4 use soilmoisture2, soilmoisture3, and soilmoisture4)
leafwetness - [%] (for sensor 2 use leafwetness2)
solarradiation - [W/m^2]
UV - [index]
visibility - [nm visibility]
indoortempf - [F indoor temperature F]
indoorhumidity - [% indoor humidity 0-100]
---
##Pollution Fields:
AqNO - [ NO (nitric oxide) ppb ]
AqNO2T - (nitrogen dioxide), true measure ppb
AqNO2 - NO2 computed, NOx-NO ppb
AqNO2Y - NO2 computed, NOy-NO ppb
AqNOX - NOx (nitrogen oxides) - ppb
AqNOY - NOy (total reactive nitrogen) - ppb
AqNO3 -NO3 ion (nitrate, not adjusted for ammonium ion) UG/M3
AqSO4 -SO4 ion (sulfate, not adjusted for ammonium ion) UG/M3
AqSO2 -(sulfur dioxide), conventional ppb
AqSO2T -trace levels ppb
AqCO -CO (carbon monoxide), conventional ppm
AqCOT -CO trace levels ppb
AqEC -EC (elemental carbon) - PM2.5 UG/M3
AqOC -OC (organic carbon, not adjusted for oxygen and hydrogen) - PM2.5 UG/M3
AqBC -BC (black carbon at 880 nm) UG/M3
AqUV-AETH -UV-AETH (second channel of Aethalometer at 370 nm) UG/M3
AqPM2.5 - PM2.5 mass - UG/M3
AqPM10 - PM10 mass - PM10 mass
AqOZONE - Ozone - ppb
softwaretype - [text] ie: WeatherLink, VWS, WeatherDisplay
'''
32 changes: 24 additions & 8 deletions src/drivers/mount.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ def __init__(self, parent = None, arg = None, name = "mount", port="", connect =
self.rate = 1

self.mount = drive(profile = 'HEQ5', mode = "eq", connectMethod = 'pymlab',
obs_lat = 48.986976, obs_lon = 14.467532, obs_alt = 300, port = '/dev/ttyUSB0')
obs_lat = 48.986976, obs_lon = 14.467532, obs_alt = 382, port = '/dev/ttyUSB0')

self.mount.run()
self.mount.UnPark()
Expand All @@ -78,6 +78,7 @@ def __init__(self, parent = None, arg = None, name = "mount", port="", connect =
#self.set_feature('mount_position',{'publish': '/mount/status/coordinates/RaDec'})
#self.set_feature('mount_offset',{'subscrib': '/mount/controll'})
self.set_feature('mount_slew',{'subscrib': '/mount/controll', 'publish': '/mount/status/coordinates/RaDec'})
self.set_feature('mount_tracking',{'subscrib': '/mount/controll', 'publish': '/mount/status/coordinates/RaDec'})
self.set_feature('mount_skymap',{})
#self.set_feature('mount_info',{'type': 'HEQ5', 'mount_mode': 'eq', 'obs_lat': 10.2332, 'obs_lon': 10.2332, 'obs_alt': 10.2332})

Expand All @@ -86,7 +87,7 @@ def __init__(self, parent = None, arg = None, name = "mount", port="", connect =
rate = rospy.Rate(self.rate)
ra = 0
dec = 90
rospy.Timer(rospy.Duration(2), self.send_position, oneshot=False)
rospy.Timer(rospy.Duration(1), self.send_position, oneshot=False)
while not rospy.is_shutdown():
try:
if len(btn_data) > 0:
Expand All @@ -111,13 +112,27 @@ def __init__(self, parent = None, arg = None, name = "mount", port="", connect =

elif "radec" in lastBtn:
split = lastBtn.split(" ")
self.mount.Slew(SkyCoord(alt = float(split[1]), az = float(split[2]), obstime = Time.now(), frame = 'altaz', unit="deg", location = self.mount.getObs()).icrs)
self.mount.Slew(SkyCoord(ra = float(split[1]), dec = float(split[2]), obstime = Time.now(), unit="deg", location = self.mount.getObs()).icrs)

elif "tle" in lastBtn:
split = lastBtn.split(" ")
self.mount.StartTrackingTLE(name = split[1])
#self.mount.Slew(SkyCoord(alt = float(split[1]), az = float(split[2]), obstime = Time.now(), frame = 'altaz', unit="deg", location = self.mount.getObs()).icrs)

elif "resetMount" in lastBtn:
self.mount.Reset()

elif "spd" in lastBtn:
split = lastBtn.split(" ")
self.mount.setTrackingSpeed(ra = float(split[1]), dec = float(split[2]))
self.mount.tracking(True)

elif "startTracking" in lastBtn:
self.mount.tracking(True)

elif "stopTracking" in lastBtn:
self.mount.tracking(False)

elif lastBtn == 'home' or lastBtn == 'KEY_STOP':
self.mount.GoPark()

Expand Down Expand Up @@ -178,11 +193,12 @@ def __init__(self, parent = None, arg = None, name = "mount", port="", connect =
self.connection.close()

def send_position(self, object):
print "send position :)"
coord = self.mount.getCoordinates()
#return (coord.ra.degree, coord.dec.degree)
mat = Float32MultiArray(data=[coord.ra.degree, coord.dec.degree])
self.pub_radec.publish(mat)
try:
coord = self.mount.getCoordinates()
mat = Float32MultiArray(data=[coord.ra.degree, coord.dec.degree])
self.pub_radec.publish(mat)
except Exception, e:
print e



Expand Down
2 changes: 1 addition & 1 deletion src/initPymlab.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@

i2c2 = str({
"device": "serial",
"port": '/dev/ttyUSB2',
"port": '/dev/ttyUSB0',
})
bus2 = str([
{
Expand Down
Loading

0 comments on commit 53e0148

Please sign in to comment.