Skip to content

Commit

Permalink
add camera driver ImaginSource, pymlab server: multiple param pass, w…
Browse files Browse the repository at this point in the history
…eatherstation: add dewdeffender, PID, ...
  • Loading branch information
roman-dvorak committed May 8, 2016
1 parent 52e027c commit 9373ebc
Show file tree
Hide file tree
Showing 8 changed files with 532 additions and 52 deletions.
18 changes: 18 additions & 0 deletions cfg/test.json
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,14 @@
"_local_storage": "/home/odroid/capture/",
"_path_structure": "std"
},
{
"type": "camera",
"name": "dfk",
"civil_name": "Kamera DFK",
"parent": "dalekohled",
"port": "",
"driver": "ImaginSource"
},
{
"type": "focuser",
"name": "cam_camera",
Expand All @@ -44,6 +52,16 @@
"name": "aws",
"driver": "AWS01B"
},
{
"type": "weatherStation",
"name": "wu",
"driver": "WEATHERCLOUD"
},
{
"type": "weatherStation",
"name": "dd",
"driver": "DEWDEFF01A"
},
{
"type": "userInterface",
"name": "lcd",
Expand Down
3 changes: 3 additions & 0 deletions src/ROSpymlabServer.py
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,9 @@ def drive(self, cfg): # zpracovava requesty ostatatich nodu
try:
if parameters == "" or parameters == None:
reval = getattr(self.devices[cfg.device], cfg.method)()
elif isinstance(eval(parameters), tuple):
print "tuple eoeoeoeoeeoeeoe", eval(parameters)
reval = getattr(self.devices[cfg.device], cfg.method)(*eval(parameters))
else:
reval = getattr(self.devices[cfg.device], cfg.method)(eval(parameters))
self.pymlab_read = False
Expand Down
24 changes: 12 additions & 12 deletions src/aromBrain.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,13 @@
#from drivers import devices
#from drivers import camera
#from drivers import focuser
from drivers import weatherStation
##from drivers import weatherStation
#from drivers import rotator
#from drivers import roof
#import drivers


class AromBrain():
def mountSlew(self, cor = [0,0]):
pass

def __init__(self):
rospy.init_node('AROM_brain')
Expand Down Expand Up @@ -51,22 +49,24 @@ def RegisterDriver(self, srv):
return 1

def NodeInfo(self, srv):
print srv
## Ziska parametry nodu dle jmena
if srv.mode == "GetNode":
return arom.srv.NodeInfoResponse(data = repr(self.devices['srv.data']), state = True)
if srv.type == "GetNode":
return arom.srv.NodeInfoResponse(data = repr(self.devices['srv.data']), done = True)

## Ziska seznam vsech nodu s parametrama
elif srv.mode == "GetAllNodes":
return arom.srv.NodeInfoResponse(data = repr(self.devices), state = True)
elif srv.type == "GetAllNodes":
print self.devices
return arom.srv.NodeInfoResponse(data = repr(self.devices), done = True)

## Ziska seznam nodu podle device .. napr podle mount, camera, ...
elif srv.mode == "GetDeviceNode":
rospy.logerr("Error: NotImplemented: %s" %(srv.mode))
return arom.srv.NodeInfoResponse(data = repr("Error: NotImplemented"), state = True)
elif srv.type == "GetDeviceNode":
rospy.logerr("Error: NotImplemented: %s" %(srv.type))
return arom.srv.NodeInfoResponse(data = repr("Error: NotImplemented"), done = True)

else:
rospy.logerr("Error: Unknown data mode in 'srv.NodeInfo': %s" %(srv.mode))
return arom.srv.NodeInfoResponse(data = repr("Error: Unknown data mode in 'srv.NodeInfo'"), state = True)
rospy.logerr("Error: Unknown data type in 'srv.NodeInfo': %s" %(srv.type))
return arom.srv.NodeInfoResponse(data = repr("Error: Unknown data type in 'srv.NodeInfo'"), done = True)


def loadDriver(self, deviceType = None, driverName = 'mount'):
Expand Down
87 changes: 86 additions & 1 deletion src/drivers/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,13 @@
from arom.srv import *
from arom.msg import *
from astropy.time import Time

import gphoto2 as gp

import getopt
import Image
import unicap


class Camera(object):
def __init__(self, arg = None, connect = True, var = {}):
Expand All @@ -25,6 +30,7 @@ def __init__(self, arg = None, connect = True, var = {}):
self.civil_name = arg['civil_name']
self.name = arg['name']
self.variables = var
self.properties = {}

##
## Inicializace vlastniho ovladace
Expand Down Expand Up @@ -96,7 +102,7 @@ def init(self):

def run(self):
try:
print "bla"
print "bla"
except Exception, e:
rospy.logerr(e)

Expand Down Expand Up @@ -148,6 +154,85 @@ def connect(self):
}
)

######################################################################################
######################################################################################
## ##
## Driver for --AWS01A-- MLAB weather station ##
## ============================================ ##
## ##
## ##
######################################################################################

class ImaginSource(Camera):
def init(self):
self.device_id = False
self.filetype = 'jpg'
print "ImaginSource driver loaded"


def run(self):
try:
print "bla"
self.capture()
except Exception, e:
rospy.logerr(e)

def connect(self):
print "-s-----------------"
print "connect"
print unicap.enumerate_devices()
if not self.device_id:
self.device_id = unicap.enumerate_devices()[1]['identifier']

self.device = unicap.Device( self.device_id )

print self.device.enumerate_formats()

if self.filetype == 'jpg':
self.filetype = 'jpeg'

props = self.device.enumerate_properties()
print "----", props
for prop in props:
print prop['identifier'], ">>", prop

try:
prop = self.device.get_property( 'frame rate' )
prop['value'] = 5.0
self.device.set_property( prop )
except Exception, e:
print e

try:
prop = self.device.get_property( 'shutter' )
prop['value'] = 29.0
self.device.set_property( prop )
except Exception, e:
print e


try:
prop = self.device.get_property( 'Gain' )
prop['value'] = 32.0
self.device.set_property( prop )
except Exception, e:
print e


self.device.start_capture()

def capture(self, name = "aaa.jpg", imgnum = 5, maximgnum = 10):
try:
buf = self.device.wait_buffer(60)
print buf

rgbbuf = buf.convert( 'RGB3' )

img = Image.fromstring( 'RGB', rgbbuf.format['size'], rgbbuf.tostring() )
img.save( name, self.filetype )

except Exception, e:
print e



Expand Down
72 changes: 51 additions & 21 deletions src/drivers/mount.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ def __init__(self, parent = None, arg = None, name = "EQmod", port="/dev/ttyUSB0
self.mountParams['trackingOffTime'] = Time.now()
self.mountParams['trackingOffCoordinates'] = self.mountParams['coordinates'].transform_to(AltAz(obstime = Time.now(), location=self.observatory['coordinates'])).to_string('dms')


self.init_time = Time.now()
self.DayLenght = {
'solar': (24.0*60*60),
Expand Down Expand Up @@ -107,15 +106,11 @@ def __init__(self, parent = None, arg = None, name = "EQmod", port="/dev/ttyUSB0
### Ovladac pujde ukoncit
###**************************************************

rate = rospy.Rate(1)
rate = rospy.Rate(10)
while not rospy.is_shutdown():
slew_err = 0.01
if self.newTarget > 0:
pass
pos = self.getPosition()
posaltaz = pos.transform_to(AltAz(obstime = Time.now(), location=self.observatory['coordinates']))
self.pub_mount_position.publish("%f;%f;%f;%f;" %(pos.ra.degree, pos.dec.degree, pos.altaz.alt.degree, posaltaz.az.degree))

#pos = self.getPosition('mount')
#posaltaz = pos.transform_to(AltAz(obstime = Time.now(), location=self.observatory['coordinates']))
#self.pub_mount_position.publish("%f;%f;%f;%f;" %(pos.ra.degree, pos.dec.degree, posaltaz.alt.degree, posaltaz.az.degree))
rate.sleep()

self.stop()
Expand All @@ -129,6 +124,7 @@ def __init__(self, parent = None, arg = None, name = "EQmod", port="/dev/ttyUSB0

def recieveHandler(self, msg):
if msg.type == 'function':
print msg.name
try:
if msg.data != '':
result = getattr(self, str(msg.name))(eval(msg.data))
Expand Down Expand Up @@ -205,10 +201,15 @@ def advSync(self, param = None):
coord = SkyCoord(alt=float(param['alt']), az=float(param['az']), frame='altaz', unit='deg', obstime = Time.now(), location = self.observatory['coordinates']).icrs
print "request on 'advSync", param, coord
self.mountParams['coordinates'] = coord
self.sync()

def sync(self, param = None):
param = eval(param)
self.mountParams['coordinates'] = SkyCoord(ra=param.ra, dec=param.dec, unit='degree', obstime=Time.now(), frame='icrs')
if not self.mountParams['tracking']:
self.mountParams['trackingOffTime'] = Time.now()
altazframe = AltAz(obstime = self.mountParams['trackingOffTime'], location=self.observatory['coordinates'])
self.mountParams['trackingOffCoordinates'] = self.mountParams['coordinates'].transform_to(altazframe).to_string('dms')

def advTrack(self, param = None):
param = eval(param)
Expand Down Expand Up @@ -377,6 +378,7 @@ def init(self):
self.driverSyncTime = Time.now()
self.coord_instrument_old = (0,0,Time.now())


##
## Registrace ovladace jako mount
##
Expand Down Expand Up @@ -486,18 +488,27 @@ def connect(self, port="/dev/ttyUSB0"):

rospy.loginfo("Steps per revolution: %s and per degree %s" %(repr(self.mountParams['StepsPerRev']), repr(self.mountParams['StepsPerDeg'])))


print "getPosition('SkyCoord') >> ", self.getPosition("SkyCoord")
self.getPosition()

self.coord_instrument_old = (0,self.stepsPerRev[1]/2,Time.now())
self._axisCountReset()

def _axisCountReset(self):
self.mountParams['RefData_ax1'] = self.Revu24str2long(self._GetData(self.GetAxisPosition, self.Axis1))
self.mountParams['RefData_ax2'] = self.Revu24str2long(self._GetData(self.GetAxisPosition, self.Axis2))
self.mountParams['RefData_time'] = Time.now()
altazframe = AltAz(obstime = self.mountParams['RefData_time'], location=self.observatory['coordinates'])
self.mountParams['RefData_coordination'] = self.mountParams['coordinates'].transform_to(altazframe).to_string('dms')

def _axisCountPos(self):
return self.getPosition('mount')

def slew(self, target = [None, None], unit = 'deg'):
if target[0] != None and target[1] != None:
self.mountParams['coordinates_target'] = SkyCoord(int(target[0]), int(target[1]), unit = unit)
self.setPosition()


def track(self, param = None):
if self.mountParams['tracking'] == True:
ra = self._GetData(self.SetMotionMode, self.Axis1, '20') # reverse - '21'
Expand Down Expand Up @@ -574,15 +585,15 @@ def setTimeMachine(self, on=None, mode=None):

def setPosition(self, param = None):
try:
self.getPosition()
print "spocitana poloha:", self.getPosition()
actual = self.getPosition('mount')
print "spocitana poloha:", actual
print "cilova poloha:", self.mountParams['coordinates_target']
change = [0,0]
change[0] = Angle(Angle(self.mountParams['coordinates_target'].ra) - Angle(self.getPosition().ra))
change[1] = Angle(Angle(self.mountParams['coordinates_target'].dec) - Angle(self.getPosition().dec)).wrap_at('90d')
change[0] = Angle(Angle(self.mountParams['coordinates_target'].ra) - Angle(actual.ra))
change[1] = Angle(Angle(self.mountParams['coordinates_target'].dec) - Angle(actual.dec)).wrap_at('90d')

print "****************** SET POSITION **********************"
rospy.loginfo( "Delta: [%s, %s] start: [%s] cil: [%s]"%( str(change[0].degree),str(change[1].degree) , str(self.getPosition().to_string('dms')), str(self.mountParams['coordinates_target'].to_string('dms'))))
rospy.loginfo( "Delta: [%s, %s] start: [%s] cil: [%s]"%( str(change[0].degree),str(change[1].degree) , str(actual.to_string('dms')), str(self.mountParams['coordinates_target'].to_string('dms'))))

##
## Vyber smeru otaceni
Expand Down Expand Up @@ -653,6 +664,13 @@ def setPosition(self, param = None):
print e


#self.mountParams['RefData_ax1'] = self._GetData(self.GetAxisPosition, self.Axis1)
#self.mountParams['RefData_ax2'] = self._GetData(self.GetAxisPosition, self.Axis2)
#self.mountParams['RefData_time'] = Time.now()
#self.mountParams['RefData_coordination'] = self.mountParams['coordinates_target'].transform_to(altazframe).to_string('dms')
self._axisCountReset()


except Exception, e:
rospy.logerr("Error in setCoordinates: %s" %(e))
#print e
Expand All @@ -661,11 +679,11 @@ def setPosition(self, param = None):
return self.mountParams['coordinates_target']

def getPosition(self, Type = None):
if self.mountParams['tracking'] == True:
coordinates = self.mountParams['coordinates']
elif self.mountParams['tracking'] == False:
print "--------------------------- ", self.mountParams['trackingOffCoordinates']
coordinates = SkyCoord(self.mountParams['trackingOffCoordinates'], unit='deg', obstime = Time.now(), frame = 'altaz', location = self.observatory['coordinates']).icrs
#if self.mountParams['tracking'] == True:
coordinates = self.mountParams['coordinates']
#elif self.mountParams['tracking'] == False:
# print "--------------------------- ", self.mountParams['trackingOffCoordinates']
# coordinates = SkyCoord(self.mountParams['trackingOffCoordinates'], unit='deg', obstime = Time.now(), frame = 'altaz', location = self.observatory['coordinates']).icrs

if Type == None:
try:
Expand All @@ -686,6 +704,18 @@ def getPosition(self, Type = None):
except Exception, e:
rospy.logerr("Error in getPosition: %s" %(e))

elif Type == 'mount':
ax_1 = self.Revu24str2long(self._GetData(self.GetAxisPosition, self.Axis1))
ax_2 = self.Revu24str2long(self._GetData(self.GetAxisPosition, self.Axis2))
Delta_time = Time.now().unix - self.mountParams['RefData_time'].unix
Delta_ra = Angle((int(self.mountParams['RefData_ax1']) - int(ax_1)) / self.mountParams['StepsPerDeg'][0], unit='deg')
Delta_dec= Angle((int(self.mountParams['RefData_ax2']) - int(ax_2)) / self.mountParams['StepsPerDeg'][1], unit='deg').wrap_at('90d')
print "rozdil zpusobeny casem:", Angle(float(Delta_time)*(15.0/3600.0), unit='deg')
print "rozdil zpusobeny montazi:", Delta_ra, Delta_dec
out = SkyCoord(coordinates.ra + Delta_ra, (coordinates.dec + Delta_dec).wrap_at('90d'))
print out
return out

elif Type == 'SkyCoord':
return coordinates

Expand Down
Loading

0 comments on commit 9373ebc

Please sign in to comment.