Merge remote-tracking branch 'origin/merge-replace' into dingo

This commit is contained in:
Ferdi Franceschini
2013-02-26 01:35:58 +11:00
32 changed files with 1319 additions and 95 deletions

View File

@@ -64,6 +64,12 @@ int main(int argc, char *argv[])
if (argv[i][0] == '-') {
if (strcasecmp(argv[i], "-nolog") == 0) {
SICSLogEnable(0);
#ifdef SITE_ANSTO
} else if (strcasecmp(argv[i], "-v") == 0) {
extern void SiteReportVersion(void);
SiteReportVersion();
return 0;
#endif
} else if (strcasecmp(argv[i], "-d") == 0) {
daemonize = 1;
} else {

View File

@@ -634,8 +634,11 @@ static hdbCallbackReturn SICSNotifyCallback(pHdb node, void *userData,
}
formatNameValue(protocol, pPath, GetCharArray(printedData), result,
mm->v->dataType);
/* SCWrite(cbInfo->pCon, GetCharArray(result), outCode); */
#ifdef SITE_ANSTO
SCWrite(cbInfo->pCon, GetCharArray(result), outCode);
#else
SCPureSockWrite(cbInfo->pCon, GetCharArray(result), outCode);
#endif
DeleteDynString(printedData);
} else {
formatNameValue(protocol, pPath, "!!datachange!!", result, HIPTEXT);

View File

@@ -22,6 +22,7 @@ PSI_SLIBS = matrix/libmatrix.a
PSI_LIBS = \
$(LIB_TCL8) $(LIB_HDF5) -lpthread \
-ldl -lz -lm -lc $(LIB_MXML) $(LIB_JSON)
PSI_CFLAGS += -DSITE_ANSTO=1
../%.o : ../%.c
cd ..; $(CC) -c $(PSI_CFLAGS) $*.c -o $*.o

View File

@@ -41,6 +41,11 @@ else
then
SICS_VER="$(git branch | grep '^*' | sed 's/^\* *//')"
SICS_REV="$(git log -1 --oneline | cut -d ' ' -f 1)"
SICS_PLUS="$(git status --porcelain -uno | wc -l)"
if [[ ${SICS_PLUS} > 0 ]]
then
SICS_REV="${SICS_REV}+${SICS_PLUS}"
fi
else
SICS_VER="$USER"
SICS_REV="$(date '+%Y-%m-%d-%H-%m-%S')"

View File

@@ -0,0 +1,91 @@
#!/usr//bin/env python
# vim: ts=8 sts=4 sw=4 expandtab
# Author: Douglas Clowes (dcl@ansto.gov.au) 2012-06-29
from twisted.internet import reactor
from twisted.python import log
from twisted.internet.task import LoopingCall
import random
import re
import sys
import time
import inspect
from galilfactory import GalilFactory
from counterclient import CounterClientFactory
from powdersample import CubicPowderSample
log.startLogging(sys.stdout)
beam_monitor_counter = None
detector_counter = None
beam_monitor_rate = None
nickel = CubicPowderSample()
def stopCallbackM1M2(motor):
global nickel
global beam_monitor_rate
mu = m2.getPosition() / 2.0
nickel.set_wavelength_from_theta_pg002(mu)
x = m1.getPosition()
y = nickel.funx(abs(x), abs(mu), 0.2)
baseline = 1000
height = int(5000 * y) + baseline
beam_monitor_rate = height
print "My Height at", x, "is", height
if beam_monitor_counter:
beam_monitor_counter.setCountRate(height)
if detector_counter:
stopCallbackS2(m1)
print "Motor M1, M2 at:", m1.getPosition(), m2.getPosition(), ", wavelength=", nickel.wavelength, ", mEv=", nickel.mEv
def stopCallbackS2(motor):
global nickel
global beam_monitor_rate
if beam_monitor_rate == None:
m1.stopCallback(m1)
x = s2.getPosition()
y = nickel.calc(abs(x))
baseline = 2000
height = int(beam_monitor_rate * y) + baseline
print "My Height at", x, "is", height
if detector_counter:
detector_counter.setCountRate(height)
print "Motor S2 at:", s2.getPosition()
def device_iterator():
now = time.time()
m1.doIteration(now)
m2.doIteration(now)
s2.doIteration(now)
basePort = 62034 # Echidna
basePort = 62134 # Wombat
basePort = 62430 # Quokka
basePort = 62730 # Taipan
devices = {}
for dev in range(0, 6):
port = basePort + dev
controllerName = "mc%d" % (dev + 1)
factory = GalilFactory(port)
devices[controllerName] = factory.device
reactor.listenTCP(port, factory)
s2 = devices["mc2"].motors["F"]
s2.moveCallback = s2.stopCallback = stopCallbackS2
m1 = devices["mc3"].motors["E"]
m1.moveCallback = m1.stopCallback = stopCallbackM1M2
m2 = devices["mc1"].motors["F"]
m2.moveCallback = m2.stopCallback = stopCallbackM1M2
m1.stopCallback(m1)
m2.stopCallback(m2)
s2.stopCallback(s2)
beam_monitor_counter = CounterClientFactory()
detector_counter = CounterClientFactory()
connector1 = reactor.connectTCP("localhost", 33001, beam_monitor_counter)
connector2 = reactor.connectTCP("localhost", 33000, detector_counter)
print "Connector1:", connector1.getDestination()
print "Connector2:", connector2.getDestination()
lc = LoopingCall(device_iterator)
lc.start(0.05)
reactor.run()

View File

@@ -0,0 +1,52 @@
#!/usr//bin/env python
# vim: ts=8 sts=4 sw=4 expandtab
# Author: Douglas Clowes (dcl@ansto.gov.au) 2012-06-29
from twisted.internet.protocol import Protocol
from twisted.internet.protocol import ReconnectingClientFactory
myCounters = {}
class Counter(Protocol):
def dataReceived(self, data):
print "Data:", data
def connectionMade(self):
print "connectionMade", self.transport.getHost(), self.transport.getPeer()
def connectionLost(self, reason):
print "connectionLost"
def sendMessage(self, m):
self.transport.write(m)
class CounterClientFactory(ReconnectingClientFactory):
def __init__(self):
self.device = None
def startedConnecting(self, connector):
print 'Started to connect.'
def buildProtocol(self, addr):
global myCounters
print 'Connected to:', addr
self.resetDelay()
p = Counter()
myCounters[addr.port] = p
self.device = p
print "My Counters", myCounters
return p
def clientConnectionLost(self, connector, reason):
global myCounters
print 'Lost connection', connector.getDestination().port,'Reason:', reason
del myCounters[connector.getDestination().port]
self.device = None
ReconnectingClientFactory.clientConnectionLost(self, connector, reason)
def clientConnectionFailed(self, connector, reason):
print 'Connection failed. Reason:', reason
ReconnectingClientFactory.clientConnectionFailed(self, connector,reason)
def setCountRate(self, rate):
if self.device:
self.device.sendMessage("SET SOURCE=%d\r\n" % rate)

View File

@@ -0,0 +1,215 @@
#!/usr//bin/env python
# vim: ts=8 sts=4 sw=4 expandtab
# Author: Douglas Clowes (dcl@ansto.gov.au) 2012-06-29
import string
import time
import re
from galilmotor import GalilMotor
class GalilController(object):
"""Galil Controller motor controller object"""
def __init__(self, thePort):
print "GalilController ctor: %d" % int(thePort)
self.port = thePort
self.motors = {}
for letter in "ABCDEFGH":
self.motors[letter] = GalilMotor(letter)
self.reset_powerup()
def reset_powerup(self):
print self.__class__.__name__, "reset_powerup"
self.variables = {}
def write(self, response):
#print "Device Response: %s" % response
self.response.append(response)
def doIteration(self, now):
#print "DoIteration"
# pass to motors
for letter in "ABCDEFGH":
self.motors[letter].doIteration(now)
def doAssignment(self, cmd, arg):
action = cmd[0:2]
axis = cmd[2:]
#print "Assignment %s(%s) = %s" % (action, axis, arg)
if action in ["PA", "SP", "AC", "DC"]:
if len(axis) == 1 and axis in "ABCDEFGH":
self.motors[axis].doAssignment(action, arg)
return
self.variables[cmd] = arg
def doCommandMG(self, cmd, arg):
#print cmd, arg
if (arg[0] == "\"" or arg[1] == "'") and arg[0] == arg[-1]:
arg = arg[1:-1]
if re.match("^CONFIG[A-H]=", arg):
the_axis = arg[6]
the_config = arg[8:]
self.motors[the_axis].doConfigure(the_config)
self.write(arg)
return
if re.match("^TRACE[A-H]=", arg):
the_axis = arg[5]
the_config = arg[7:]
self.motors[the_axis].doTrace(the_config)
self.write(arg)
return
if re.match("^DROP", arg):
self.protocol.transport.loseConnection();
return
# TODO replace this simple stuff with more complex
if re.match("^{[^}]+}", arg):
the_match = re.match("^({[^}]+})(.*)$", arg)
the_format = the_match.group(1)
the_rest = string.strip(the_match.group(2))
arg = the_rest
response = []
for item in arg.split(","):
item = string.strip(item)
#print "Item:", item
if item == "_TI0":
response.append(" 0000000000")
elif item == "_TI1":
response.append(" 0000000000")
elif item == "_XQ0":
response.append(" 0000000123")
elif len(item) == 4 and item[0] == "_":
axis = arg[3]
param = self.motors[axis].doQuery(item[1:3])
if param < 0:
paramstr = "-" + ("%010i" % abs(param))
else:
paramstr = " " + ("%010i" % param)
response.append(paramstr)
result = string.join(response, "")
#print result
self.write(result)
def doMotorCommand(self, cmd, arg):
# TODO replace this simple stuff with more complex
action = cmd[0:2]
axes = cmd[2:] + arg
for axis in axes:
self.motors[axis].doCommand(action, None)
def doCommandLV(self, cmd, arg):
code = "SIMULATE"
self.variables[code] = "1"
keys = self.variables.keys()
keys.sort()
for key in keys:
self.write("%s= %s" % (key, self.variables[key]))
del self.variables[code]
def doCommandDA(self, cmd, arg):
key = cmd[3:]
if key in self.variables.keys():
del self.variables[key]
def doCommand(self, cmd, arg):
action = cmd[0:2]
#print "Command %s(%s) = %s" % (action, cmd[2:], arg)
if action in ["BG", "ST", "TP", "TD", "SH", "MO"]:
self.doMotorCommand(cmd, arg)
if action == "LV":
self.doCommandLV(cmd, arg)
return
elif action == "DA":
self.doCommandDA(cmd, arg)
elif action == "MG":
self.doCommandMG(cmd, arg)
def processDataReceived(self, data):
#print "PDU: \"" + data + "\""
self.response = []
the_match = re.match("^([A-Z0-9_*]+)(.*)$", data)
if the_match and the_match.group(2)[:1] == "=":
cmd = the_match.group(1)
arg = the_match.group(2)[1:]
self.doAssignment(cmd, arg)
elif re.match("([A-Z][A-Z]) *(.*)$", data):
match = re.match("([A-Z][A-Z]) *(.*)$", data)
cmd = match.group(1)
arg = match.group(2)
self.doCommand(cmd, arg)
else:
print "Command not recognized:", data
cmd = "Command"
arg = "Unknown"
# TODO replace this simple stuff with more complex
#print "OUT: \"" + self.response + "\""
return self.response
def dataReceived(self, data):
self.doIteration(time.time())
return self.processDataReceived(data)
if __name__ == '__main__':
totalDistance = 100000
mc = GalilController(0)
print "LV", mc.processDataReceived("LV")
print "MG", mc.processDataReceived("MG \"TRACEA=ON\"")
print "MG", mc.processDataReceived("MG \"CONFIGA=SPX=25000.0,CPX=8192.0,RL=-10.0,FL=10.0,UH=0.0,EH=100000000\"")
print "SP", mc.processDataReceived("SPA=25000")
print "AC", mc.processDataReceived("ACA=25000")
print "DC", mc.processDataReceived("DCA=25000")
print "PA", mc.processDataReceived("PAA=%d" % totalDistance)
start_position = int(mc.processDataReceived("MG _TDA")[0])
print "SH", mc.processDataReceived("SHA")
print "BG", mc.processDataReceived("BGA")
startTime = time.time()
currentDistance = 0
print "MO", mc.processDataReceived("MG _MOA")
print "BG", mc.processDataReceived("MG _BGA")
count = 0
#previousTime = 0
while int(mc.processDataReceived("MG _BGA")[0]) == 1 and count <= 100:
t = 0.1 * count
mc.doIteration(mc.motors["A"].motorStartTime + t)
rnge = 70
temp = currentDistance
currentDistance = abs(int(mc.processDataReceived("MG _TDA")[0]) - start_position)
#percentDistance = 100.0 * currentDistance / totalDistance
#percentVelocity = 100.0 * (currentDistance - temp) / (t - previousTime) / mc.processDataReceived("MG _SPA")[0]
#previousTime = t
percentDistance = mc.motors["A"].percentDistance
percentVelocity = mc.motors["A"].percentVelocity
vspot = int(0.01 * rnge * percentVelocity)
sspot = int(0.01 * rnge * percentDistance)
bth = "b"
if sspot >= 0:
ess = "s"
else:
ess = "*"
bth = "B"
sspot = 0
if vspot >= 0:
vee = "v"
else:
vee = "^"
bth = "B"
vspot = 0
if vspot < sspot:
line = " "*(vspot) + vee + " "*(sspot - vspot - 1) + ess + " "*(rnge - sspot) + "|"
line += " %2d %2d" % (vspot, sspot)
elif vspot > sspot:
line = " "*(sspot) + ess + " "*(vspot - sspot - 1) + vee + " "*(rnge - vspot) + "|"
line += " %2d %2d" % (sspot, vspot)
else:
line = " "*(sspot) + bth + " "*(rnge - sspot) + "|"
line += " %2d" % (sspot)
print "%3.2f: %s" % (t, line)
count += 1
print "_MO", mc.processDataReceived("MG _MOA")
print "_BG", mc.processDataReceived("MG _BGA")
print "_TP", mc.processDataReceived("MG _TPA")
print "_TD", mc.processDataReceived("MG _TDA")
print "MO", mc.processDataReceived("MOA")
print "_MO", mc.processDataReceived("MG _MOA")
print "ZZ", mc.processDataReceived("ZZA")
print "_ZZ", mc.processDataReceived("MG _ZZA")
print "MG", mc.processDataReceived("MG _MOA, _BGA, _TDA, _TPA, _SPA, _ACA, _DCA")
print "Iterations:", count

View File

@@ -0,0 +1,88 @@
#!/usr//bin/env python
# vim: ts=8 sts=4 sw=4 expandtab
# Author: Douglas Clowes (dcl@ansto.gov.au) 2012-06-29
from twisted.internet.protocol import Protocol
from twisted.internet.protocol import ServerFactory
from galilcontroller import GalilController
class GalilProtocol(Protocol):
"""Protocol object used by the Twisted Infrastructure to handle connections
"""
def __init__(self, thisDevice):
print "GalilProtocol protocol ctor", thisDevice
self.device = thisDevice
self.term = "\r\n"
def write(self, response):
self.response = self.response + response
def connectionMade(self):
self.pdu = ""
self.response = ""
self.device.protocol = self
self.factory.numProtocols = self.factory.numProtocols + 1
print "connectionMade: connection number", self.factory.numProtocols
if self.factory.numProtocols > 2:
print "Too many connections - rejecting"
self.transport.write("Too many connections, try later\r\n")
self.transport.loseConnection()
'''else:
self.transport.write("Welcome connection %d\r\n" % self.factory.numProtocols)'''
def connectionLost(self, reason):
self.factory.numProtocols = self.factory.numProtocols - 1
print "connectionLost: connections left", self.factory.numProtocols
def dataReceived(self, data):
#print "dataReceived - len:", len(data)
last_was_cr = False
for c in data:
if c == "\r" or c == ";" or c == "\n":
if c == "\n" and last_was_cr:
continue
last_was_cr = False
if c == "\r":
last_was_cr = True
if len(self.pdu) > 0:
#print "Request: ", self.pdu
the_response = self.device.dataReceived(self.pdu)
#print "Response:", the_response
for item in the_response:
self.write(item + self.term)
self.pdu = ""
if c == ";":
if len(self.response) > 0 and self.response[-1] != ":":
self.response = self.response + ":"
else:
if len(self.response) > 0:
if self.response[-1] == ";":
self.response = self.response[:-1]
if len(self.response) > 0 and self.response[-1] != ":":
self.response = self.response + ":"
if len(self.response) == 0:
self.response = self.response + ":"
if len(self.response) > 0:
#print "Protocol Response: %s" % self.response
self.transport.write(self.response)
self.response = ""
else:
self.pdu = self.pdu + c
class GalilFactory(ServerFactory):
"""Factory object used by the Twisted Infrastructure to create a Protocol
object for incomming connections"""
protocol = GalilProtocol
def __init__(self, thePort):
print "GalilFactory ctor: "
self.port = thePort
self.device = GalilController(thePort)
self.numProtocols = 0
def buildProtocol(self, addr):
p = self.protocol(self.device)
p.factory = self
return p

View File

@@ -0,0 +1,350 @@
#!/usr//bin/env python
# vim: ts=8 sts=4 sw=4 expandtab
# Author: Douglas Clowes (dcl@ansto.gov.au) 2012-06-29
import inspect
import time
import math
class GalilMotor(object):
"""Galil Motor Object"""
def __init__(self, theAxis):
print "GalilMotor ctor: %s" % theAxis
self.axis = theAxis
self.motorState = "OFF"
self.stepsPerX = 25000.0
self.cntsPerX = 8192.0
self.speed = 25000
self.accel = 2500
self.decel = 2500
self.lowerLim = -20.0
self.upperLim = 20.0
self.hasAbsEnc = True
self.unitsHome = 0.0
self.absEncHome = 100 * 1000 * 1000
self.motorHome = 0.0
self.currentSteps = 0
self.targetSteps = self.currentSteps
self.configDone = False
self.switches = 44
self.stopcode = 0
self.stopCallback = None
self.moveCallback = None
self.trace = False
def doTrace(self, arg):
print "Trace %s: %s" % (self.axis, arg),
if self.trace:
print "(ON =>",
else:
print "(OFF =>",
if arg == "ON":
self.trace = True
else:
self.trace = False
if self.trace:
print "ON)"
else:
print "OFF)"
def doConfigure(self, arg):
print "Configure %s: %s" % (self.axis, arg)
the_parts = arg.split(",")
configDoneAlready = self.configDone
for part in the_parts:
(lh, rh) = part.split("=")
if lh == "SPX":
self.stepsPerX = float(rh)
self.configDone = True
elif lh == "CPX":
self.cntsPerX = float(rh)
self.configDone = True
elif lh == "RL":
self.lowerLim = float(rh)
self.configDone = True
elif lh == "FL":
self.upperLim = float(rh)
self.configDone = True
elif lh == "UH":
self.unitsHome = float(rh)
self.configDone = True
elif lh == "EH":
self.hasAbsEnc = True
self.absEncHome = float(rh)
self.configDone = True
elif lh == "MH":
self.hasAbsEnc = False
self.motorHome = float(rh)
self.configDone = True
else:
print "Unrecognized config item \"%s\" in \"%s\"" % (lh, arg)
if self.configDone and not configDoneAlready:
self.currentSteps = 0
self.targetSteps = 0
def getEncoder(self):
'''Calculate the encoder from the currentSteps'''
value = self.absEncHome + self.currentSteps * (self.cntsPerX / self.stepsPerX)
return int(value)
def getPosition(self):
'''Calculate the unit position'''
value = self.unitsHome + self.currentSteps / self.stepsPerX
value = self.getEncoder() - self.absEncHome
value /= self.cntsPerX
value += self.unitsHome
return value
def doIteration(self, now):
'''If moving then update speed and position using
v = u + at
s = ut + 1/2 at**2 = (u + v)t / 2
v**2 = u**2 + 2as
'''
if self.motorState in ["MOVING"]:
t = now - self.motorStartTime
distance = abs(self.targetSteps - self.motorStartSteps)
topSpeed = math.sqrt(2.0 * distance / ( 1.0 / self.accel + 1.0 / self.decel))
if topSpeed < 1e-6:
topSpeed = 0
if topSpeed > self.speed:
topSpeed = self.speed
t1 = topSpeed / self.accel
s1 = 0.5 * self.accel * t1**2
t3 = topSpeed / self.decel
s3 = 0.5 * self.decel * t3**2
s2 = distance - s1 - s3
if s2 < 1e-6:
s2 = 0
if s2 == 0 or topSpeed == 0:
t2 = 0
else:
t2 = s2 / topSpeed
if t >= (t1 + t2 + t3):
# Finished
s = distance
v = 0
self.motorState = "STOPPED"
self.stopcode = 1
self.switches = 44 # stopped, both limits clear
elif t >= (t1 + t2):
# Ramp Down
dt = t - (t1 + t2)
# v = u + at
v = topSpeed - self.decel * dt
# s = (u + v)t / 2
s = s1 + s2 + 0.5 * (topSpeed + v) * dt
elif t >= t1:
# Run Flat
v = topSpeed
s = s1 + topSpeed * (t - t1)
else:
# Ramp Up
v = 0.0 + self.accel * t
s = 0.5 * self.accel * t**2
if self.speed < 1e-6:
self.percentVelocity = 100.0
else:
self.percentVelocity = 100.0 * v / self.speed
if distance < 1e-6:
self.percentDistance = 100.0
else:
self.percentDistance = 100.0 * s / distance
if self.targetSteps > self.motorStartSteps:
self.currentSteps = self.motorStartSteps + int(s)
if self.currentSteps >= self.targetSteps:
self.motorState = "STOPPED"
self.stopcode = 1
self.switches = 44 # stopped, both limits clear
elif self.targetSteps < self.motorStartSteps:
self.currentSteps = self.motorStartSteps - int(s)
if self.currentSteps <= self.targetSteps:
self.motorState = "STOPPED"
self.stopcode = 1
self.switches = 44 # stopped, both limits clear
else:
self.motorState = "STOPPED"
self.stopcode = 1
self.switches = 44 # stopped, both limits clear
currentPosition = self.getPosition()
if not self.moveCallback == None:
self.moveCallback(self)
# TODO Forward Limit
# TODO Reverse Limit
if self.motorState == "STOPPED":
print "Axis %s stopped at:" % self.axis, currentPosition
self.currentSteps = self.targetSteps
if not self.stopCallback == None:
self.stopCallback(self)
else:
pass
def doAssignment(self, cmd, arg):
'''This is for commands like "PAA=1234567" which are for the motor.
The axis and the assignment operator have already been removed.
'''
if self.trace:
print "Trace ASG %s: %s" % (self.axis, str(cmd) + " " + str(arg))
if cmd == "PA":
self.targetSteps = int(arg)
elif cmd == "PR":
self.targetSteps = self.currentSteps + int(arg)
elif cmd == "SP":
self.speed = max(1, abs(int(arg)))
elif cmd == "AC":
self.accel = max(1, abs(int(arg)))
elif cmd == "DC":
self.decel = max(1, abs(int(arg)))
else:
print "Unknown assignment", cmd, arg
def doQuery(self, arg):
if arg == "TD":
response = self.currentSteps
elif arg == "ZZ":
response = self.getPosition()
elif arg == "TP":
response = self.getEncoder()
elif arg == "SP":
response = self.speed
elif arg == "AC":
response = self.accel
elif arg == "DC":
response = self.decel
elif arg == "TS":
response = self.switches
elif arg == "SC":
response = self.stopcode
elif arg == "MO":
if self.motorState in ["OFF"]:
response = 1
else:
response = 0
elif arg == "BG":
if self.motorState in ["MOVING"]:
response = 1
else:
response = 0
else:
print "Unknown Query:", arg
response = None
if self.trace:
print "Trace QRY %s: %s" % (self.axis, str(arg) + " = " + str(response))
return response
def doCommandTD(self, arg):
return self.doQuery("TD")
def doCommandZZ(self, arg):
result = self.doQuery("ZZ")
print "Position:", result
return result
def doCommandTP(self, arg):
return self.doQuery("TP")
def doCommandST(self, arg):
if self.motorState in ["MOVING"]:
self.motorState = "STOPPED"
self.stopcode = 4
self.switches = 44
return True
def doCommandBG(self, arg):
if self.motorState in ["ON", "STOPPED"]:
self.motorState = "MOVING"
self.stopcode = 0
self.switches = 140 # moving, both limits clear
self.motorStartTime = time.time()
self.motorStartSteps = self.currentSteps
return True
return False
def doCommandSH(self, arg):
if self.motorState in ["ON", "OFF", "STOPPED"]:
self.motorState = "ON"
return True
return False
def doCommandMO(self, arg):
if self.motorState in ["ON", "OFF", "STOPPED"]:
self.motorState = "OFF"
return True
return False
def doCommandPA(self, arg):
self.targetSteps = int(arg)
return True
def doCommandPR(self, arg):
self.targetSteps = self.currentSteps + int(arg)
return True
def doCommand(self, cmd, arg):
'''This is for commands like "BGA" which are for the motor.
The axis and other cruft have already been removed.
'''
action = "inspect.ismethod(GalilMotor.doCommand%s)" % cmd
if eval(action):
if self.trace:
data = cmd
if arg:
data = data + " " + arg
print "Trace CMD: \"" + data + "\""
action = "response = self.doCommand%s(%s)" % (cmd, arg)
exec action
return response
else:
print "Unknown Action:", eval(action), "for cmd:", action
if __name__ == '__main__':
motor = GalilMotor("A")
motor.doConfigure("SPX=25000.0,CPX=8192.0,RL=-10.0,FL=10.0,UH=0.0,EH=100000000")
print "SP", motor.doAssignment("SP", "25000")
print "AC", motor.doAssignment("AC", "25000")
print "DC", motor.doAssignment("DC", "25000")
print "PA", motor.doAssignment("PA", "100000")
print "SH", motor.doCommand("SH", None)
print "BG", motor.doCommand("BG", None)
print "MO", motor.doQuery("MO")
print "BG", motor.doQuery("BG")
count = 0
while motor.doQuery("BG") and count <= 100:
t = 0.1 * count
motor.doIteration(motor.motorStartTime + t)
rnge = 70
vspot = int(0.01 * rnge * motor.percentVelocity)
sspot = int(0.01 * rnge * motor.percentDistance)
bth = "b"
if sspot >= 0:
ess = "s"
else:
ess = "*"
bth = "B"
sspot = 0
if vspot >= 0:
vee = "v"
else:
vee = "^"
bth = "B"
vspot = 0
if vspot < sspot:
line = " "*(vspot) + vee + " "*(sspot - vspot - 1) + ess + " "*(rnge - sspot) + "|"
line += " %2d %2d" % (vspot, sspot)
elif vspot > sspot:
line = " "*(sspot) + ess + " "*(vspot - sspot - 1) + vee + " "*(rnge - vspot) + "|"
line += " %2d %2d" % (sspot, vspot)
else:
line = " "*(sspot) + bth + " "*(rnge - sspot) + "|"
line += " %2d" % (sspot)
print "%3.2f: %s" % (t, line)
count += 1
print "_MO", motor.doQuery("MO")
print "_BG", motor.doQuery("BG")
print "TP", motor.doCommand("TP", None)
print "TD", motor.doCommand("TD", None)
print "ZZ", motor.doCommand("ZZ", None)
print "_ZZ", motor.doQuery("ZZ")
print "MO", motor.doCommand("MO", None)
print "_MO", motor.doQuery("MO")
print "Iterations:", count

View File

@@ -0,0 +1,108 @@
#!/usr//bin/env python
# vim: ts=8 sts=4 sw=4 expandtab
# Author: Douglas Clowes (dcl@ansto.gov.au) 2012-07-18
import math
class CubicPowderSample:
def __init__(self):
self.aspacing = 3.5238 # Angstroms
self.wavelength = 2.34548 # Angstroms
self.wavelength_error = 0.00 # Angstroms
self.peakpos_error = 0.0 # degrees
self.mEv = 0.0
def set_wavelength_from_theta_pg002(self, theta):
dd = 3.35416e-10 # For Monochromator PG 0 0 2
h_for_joules = 6.62606957e-34
neutron_mass = 1.674927351e-27
ev_to_joules = 1.602176565e-19
angle = theta
myWavelength = 2.0 * dd * math.sin(angle * 3.141592654 / 180.0)
if myWavelength > 0:
temp = h_for_joules / (neutron_mass * myWavelength)
joules = 0.5 * neutron_mass * (temp * temp)
self.mEv = 1000 * joules / ev_to_joules
self.wavelength = 1e10 * myWavelength
else:
self.mEv = 0.0
self.wavelength = 0.0
print "theta = %g, wl = %g, mEv = %g" % (angle, self.wavelength, self.mEv)
def atod(self, the_aspacing, h, k, l):
result = math.sqrt(the_aspacing**2 /(h**2 + k**2 + l**2))
return result
def peak_position(self, dspacing, wavelength):
try:
theta = math.asin(wavelength / (2.0 * dspacing)) * 180 / 3.141592654
return 2.0 * theta
except:
print "error in peak_position(", dspacing, wavelength, ")"
return 0.0
def funx(self, x, mu, sigma):
try:
factor = 1.0 / (sigma * math.sqrt(2.0 * math.pi))
y = factor * math.exp(-0.5 * ((x - mu) / sigma)**2)
return y
except:
print "error in func(", x, mu, sigma, ")"
return 0.0
def calc(self, x):
peaks = []
peaks.append([0.5, 0.5, 0.5, 1.0])
peaks.append([1, 0, 0, 0.5])
peaks.append([1, 1, 0, 0.8])
peaks.append([1, 1, 1, 0.9])
peaks.append([2, 0, 0, 0.4])
peaks.append([1.5, 0.5, 0.5, 0.1])
peaks.append([2, 1, 0, 0.5])
peaks.append([2, 1, 1, 0.4])
peaks.append([2, 2, 0, 0.3])
sigma = 0.1 + 0.4 * math.sin(math.pi * x / 180.0)
y = 0.0
for peak in peaks:
peakpos = self.peak_position(self.atod(self.aspacing, peak[0], peak[1], peak[2]), self.wavelength + self.wavelength_error)
y += self.funx(x, peakpos + self.peakpos_error, sigma) * peak[3]
return y
if __name__ == '__main__':
nickel = CubicPowderSample()
px = []
for i in range(200, 891):
x = 0.1 * i
px.append(x)
from sys import argv
from mpl_toolkits.axes_grid.axislines import SubplotZero
import matplotlib.pyplot as plt
fig = plt.figure(1)
ax = SubplotZero(fig, 111)
fig.add_subplot(ax)
for direction in ["xzero", "yzero"]:
#ax.axis[direction].set_axisline_style("-|>")
ax.axis[direction].set_visible(True)
for direction in ["left", "right", "bottom", "top"]:
ax.axis[direction].set_visible(False)
if len(argv) > 1:
for i in range(1, len(argv)):
print "argv[%d]:" % i, argv[i]
nickel.set_wavelength_from_theta_pg002(float(argv[i]))
py = []
for x in px:
y = nickel.calc(x)
py.append(y)
ax.plot(px, py)
else:
py = []
for x in px:
y = nickel.calc(x)
py.append(y)
ax.plot(px, py)
print "len:", len(px), len(py)
plt.show()

View File

@@ -8,7 +8,7 @@ namespace eval ::scobj::ips120 {
# /envcont/setpoint
# /envcont/sensor/value
proc debug_log {args} {
set fd [open "/tmp/ips120.log" a]
set fd [open "../log/ips120.log" a]
puts $fd "[clock format [clock seconds] -format "%T"] $args"
close $fd
}
@@ -94,9 +94,9 @@ debug_log "setPoint new data for $tc_root [sct] result=$par"
hset $tc_root/status "busy"
sct print "status: busy"
hset $tc_root/drive_state "START"
hsetprop $tc_root/setpoint driving 1
} catch_message ]
if {$catch_status != 0} {
hsetprop $tc_root/setpoint driving 0
return -code error $catch_message
}
sct print "setPoint: [hget $tc_root/drive_state]"
@@ -455,8 +455,7 @@ debug_log "rdState $tc_root error scan status = $rslt on $my_status"
set setpoint [sct target]
set lolimit [hval $tc_root/lowerlimit]
set hilimit [hval $tc_root/upperlimit]
if {$setpoint < $lolimit || $setpoint > $hilimit} {
sct driving 0
if {$setpoint <= $lolimit || $setpoint => $hilimit} {
error "setpoint violates limits"
}
return OK
@@ -646,8 +645,8 @@ debug_log "Registering node $nodeName for write callback"
createNode $scobj_hpath $sct_controller $cmdGroup $varName $readable $writable $drivable $dataType $permission $rdCmd $rdFunc $wrCmd $wrFunc $allowedValues $klass
}
hsetprop $scobj_hpath/sensor/value lowerlimit -12
hsetprop $scobj_hpath/sensor/value upperlimit 12
hsetprop $scobj_hpath/sensor/value lowerlimit -10
hsetprop $scobj_hpath/sensor/value upperlimit 10
hsetprop $scobj_hpath/sensor/value units "T"
hfactory $scobj_hpath/apply_tolerance plain user int
@@ -745,7 +744,7 @@ debug_log "Registering node $nodeName for write callback"
# @param port, the IP protocol port number of the device
# @param _tol (optional), this is the initial tolerance setting
proc add_ips120 {name IP port {_tol 5.0}} {
set fd [open "/tmp/ips120.log" a]
set fd [open "../log/ips120.log" a]
if {[SplitReply [environment_simulation]]=="false"} {
puts $fd "makesctcontroller sct_ips120 oxford ${IP}:$port"
makesctcontroller sct_ips120 oxford ${IP}:$port
@@ -758,7 +757,7 @@ proc add_ips120 {name IP port {_tol 5.0}} {
}
puts stdout "file evaluation of sct_oxford_ips.tcl"
set fd [open "/tmp/ips120.log" w]
set fd [open "../log/ips120.log" w]
puts $fd "file evaluation of sct_oxford_ips.tcl"
close $fd

View File

@@ -11,8 +11,6 @@
source $cfPath(hipadaba)/instdict_specification.tcl
source $cfPath(hipadaba)/common_instrument_dictionary.tcl
InstallHdb
namespace eval ::hdb {
namespace export buildHDB attlist

View File

@@ -76,6 +76,15 @@ proc ::scan::hmm_scan_collect {sobj uobj point} {
clientput "Monitor $bmn [SplitReply [$bmon getcounts]]"
}
}
proc ::scan::hmscanend_event {} {
::scan::runscan_cmd -set feedback status IDLE
}
publish ::scan::hmscanend_event user
proc ::scan::bmonscanend_event {} {
::scan::hdb_bmonscan -set feedback status IDLE
}
publish ::scan::bmonscanend_event user
proc ::scan::ic_initialize {} {
if [ catch {
@@ -117,6 +126,8 @@ proc ::scan::ic_initialize {} {
savetype text=save,nosave
force boolean
}]
scriptcallback connect hmscan SCANEND ::scan::hmscanend_event
scriptcallback connect bmonscan SCANEND ::scan::bmonscanend_event
} message ] {
if {$::errorCode=="NONE"} {return $message}
return -code error $message

View File

@@ -1,8 +1,6 @@
#!/bin/bash
# $Revision: 1.28.10.1 $
# $Date: 2010-01-27 03:15:13 $
#!/bin/bash
# Author: Ferdi Franceschini (ffr@ansto.gov.au)
# Last revision by $Author: jgn $
# Author: Douglas Clowes (dcl@ansto.gov.au)
# Deploys SICServer and configuration files to
# an instrument control computer.
@@ -54,8 +52,10 @@ copy_server_config() {
fi
}
# Set shell matches to be case insensitive
shopt -s nocasematch
# If the first argument is "-n" then it is a dry-run only
if [[ "$1" = "-n" ]]
then
DEPLOY="NO"
@@ -64,12 +64,17 @@ else
DEPLOY="YES"
fi
# If the wrong number of arguments is given, print usage info and exit
if [ $# -eq 0 -o $# -gt 3 ]
then
usage
exit 1
fi
# Allow test/animal or animal/test or just animal
# animal produces TESTING=".", INSTRUMENT=animal
# test/animal produces TESTING=test, INSTRUMENT=animal
# animal/test produces TESTING=animal, INSTRUMENT=test (we then swap them)
TESTING=$(dirname "$1")
INSTRUMENT=$(basename "$1")
if [[ "$INSTRUMENT" = "test" ]]
@@ -81,7 +86,10 @@ fi
SRCDIR="."
TEMPDIR=$HOME/tmp
# We allow the instrument to be specified as either the animal name or the
# mnemonic as we have to map between the two. This is because the source
# directory is named by the mnemonic and the destination directory is named by
# the animal. Any instrument-specific processing should be done within the case.
# Set the destination host
# instrument name and the
@@ -138,8 +146,10 @@ INSTSRC=$SRCDIR/dingo;;
esac
INSTCFDIR=$INSTSRC/config
# Perform any instrument-specific make processing
make -C ../ $INSTRUMENT || exit $?
# Set up the staging directories and, if testing, the testing parts
if [[ "$TESTING" = "test" ]]
then
DESTHOST=${2:-ics1-test.nbi.ansto.gov.au}
@@ -162,8 +172,10 @@ else
mkdir -p $TEMPDIR/$DESTDIR
fi
# Notify progress and intention
echo "Deploying $INSTRUMENT to $DESTHOST:$DESTDIR"
# Set up the commands that we will be using for the "deploy" phase
EXTRACT_CMDS="tar vxzp -C /; touch /$DESTDIR/{DataNumber,extraconfig.tcl,newserver/config/nexus/nexus.dic,script_validator/DataNumber}"
if [[ "$DESTHOST" = "localhost" ]]
then
@@ -178,6 +190,7 @@ EXTRACT="ssh $DESTHOST $EXTRACT_CMDS"
EXTRACT_NODEPLOY="ssh $DESTHOST $EXTRACT_CMDS"
fi
# Ensure that we have the needed manifest files
if [ ! -e $SRCDIR/MANIFEST.TXT ]
then
echo "$SRCDIR/MANIFEST.TXT not found"

View File

@@ -21,7 +21,11 @@ config/environment/temperature/sct_julabo_lh45.tcl
config/environment/temperature/sct_lakeshore_340.tcl
config/environment/temperature/sct_lakeshore_336.tcl
config/environment/temperature/sct_qlink.tcl
config/environment/temperature/sct_watlow_st4.tcl
config/environment/temperature/sct_rvasm2.tcl
config/environment/temperature/sct_oxford_itc.tcl
config/environment/magneticField/sct_bruker_BEC1.tcl
config/environment/magneticField/sct_oxford_ips.tcl
config/environment/magneticField/sct_oxford_labview.tcl
config/motors/sct_jogmotor_common.tcl

View File

@@ -1,3 +1,5 @@
# Forbid detector motion when the detector voltage is on
forbid {-inf inf} for det when dhv1 in {800 inf}
forbid {-inf inf} for detoff when dhv1 in {800 inf}
forbid {-inf 625} for det when hez in {-inf 647}
forbid {-inf inf} for hez when det in {-inf 625}

View File

@@ -16,6 +16,21 @@ switch [string tolower $envtemp] {
}
}
}
"brukerjulabo" {
add_bruker_BEC1 ma1 137.157.202.80 4444 0.1
add_lh45 tc1 137.157.202.78 4003 0.5
proc ::histogram_memory::pre_count {} {
catch {
hset /sample/tc1/sensor/start_temperature [hval /sample/tc1/sensor/value]
hset /sample/tc1/sensor/end_temperature [hval /sample/tc1/sensor/value]
}
}
proc ::histogram_memory::post_count {} {
catch {
hset /sample/tc1/sensor/end_temperature [hval /sample/tc1/sensor/value]
}
}
}
"rhqc" {
puts "Configuring RHQC"
# 9600 8 1 None None Enable
@@ -56,6 +71,49 @@ switch [string tolower $envtemp] {
tuning 0
interval 10
}
hfactory /sics/tc2/sensor/start_sensorValueA plain user float
hfactory /sics/tc2/sensor/end_sensorValueA plain user float
# ::scobj::hinitprops tc2 sensor/start_sensorValueA sensor/end_sensorValueA
hsetprop /sics/tc2/sensor/start_sensorValueA nxalias start_sensorValueA
hsetprop /sics/tc2/sensor/end_sensorValueA nxalias start_sensorValueB
foreach {prop propval} {
control true
data true
nxsave true
mutable true
klass parameter
sdsinfo ::nexus::scobj::sdsinfo
long_name tc2
} {
hsetprop /sics/tc2/sensor/start_sensorValueA $prop $propval
hsetprop /sics/tc2/sensor/end_sensorValueA $prop $propval
}
proc ::histogram_memory::pre_count {} {
catch {
set fPath "magnetic"
hset /sics/$fPath/start_magnetic [hval /sics/$fPath/magneticField]
hset /sics/$fPath/start_temperature_s1 [hval /sics/$fPath/Temp_s1]
hset /sics/$fPath/start_temperature_s2 [hval /sics/$fPath/Temp_s2]
hset /sics/$fPath/start_temperature_s3 [hval /sics/$fPath/Temp_s3]
# Set lakeshore temperatures at start of acquisition
hset /sample/tc2/sensor/start_sensorValueA [hval /sample/tc2/sensor/sensorValueA]
hset /sample/tc2/sensor/end_sensorValueA [hval /sample/tc2/sensor/sensorValueA]
}
}
proc ::histogram_memory::post_count {} {
catch {
set fPath "magnetic"
hset /sics/$fPath/end_magnetic [hval /sics/$fPath/magneticField]
hset /sics/$fPath/end_temperature_s1 [hval /sics/$fPath/Temp_s1]
hset /sics/$fPath/end_temperature_s2 [hval /sics/$fPath/Temp_s2]
hset /sics/$fPath/end_temperature_s3 [hval /sics/$fPath/Temp_s3]
# Set lakeshore temperature at end of acquisition
hset /sample/tc2/sensor/end_sensorValueA [hval /sample/tc2/sensor/sensorValueA]
}
}
}
"11tmagnetvti" {
puts "Configuring 11TMagnet with VTI"

View File

@@ -1,12 +1,12 @@
fileeval $cfPath(environment)/magnetic/sct_oxford_labview.tcl
fileeval $cfPath(environment)/magneticField/sct_oxford_labview.tcl
# PORT 22
# PORT 55001
::scobj::magnetic::mkMagnetic {
name "magnetic"
IP 137.157.201.91
PORT 55001
IP 137.157.202.80
PORT 22
tuning 0
interval 10
interval 3
}

View File

@@ -1,6 +1 @@
# Detector voltage controller
fileeval $cfPath(hmm)/sct_orhvps_common.tcl
::scobj::dethvps::init ca1-quokka 4001 4.1
dhv1 max 2600
dhv1 lower 19
dhv1 upper 57
fileeval $cfPath(hmm)/ordela_detector_config.tcl

View File

@@ -2,19 +2,46 @@
proc ord_get_pot { potxy potnumber } {
for { set rsp "Bad" } { $rsp == "Bad" } { } {
set potname [ format "%s%d" $potxy [expr $potnumber ^ 3] ]
# set potname [ format "%s%d" $potxy [expr $potnumber ^ 3] ]
# set rspall [ dhv1 cmd P $potname ]
set rspall [ sct_dhv1 transact "P $potname" ]
# NOTE: new driver (ie sct_dhv) re-orders lower 2 bits
set potname [ format "%s%d" $potxy $potnumber ]
set rspall [ sct_dhv transact "P $potname" ]
set rsp [lindex [split $rspall " "] 1]
# MJL sometimes the driver returns '=' or '', fix that...
# ALSO the driver sometimes returns TCL internal strings, reject non-numeric data
# ALSO the driver sometimes returns 65, fix that (range 0 to 63)
set rspval 0
if { $rsp == "=" || $rsp == "" || [scan $rsp %d rspval] != 1 } { set rsp "Bad" }
if { $rspval < 0 } { set rspval 0 }
if { $rspval > 63 } { set rspval 63 }
}
return $rsp
return $rspval
}
Publish ord_get_pot User
proc ord_set_pot { potxy potnumber potvalue } {
set potname [ format "%s%d" $potxy [expr $potnumber ^ 3] ]
# set potname [ format "%s%d" $potxy [expr $potnumber ^ 3] ]
# set rsp [ dhv1 cmd p $potname $potvalue ]
set rsp [ sct_dhv1 transact "p $potname $potvalue" ]
# NOTE: new driver (ie sct_dhv) re-orders lower 2 bits
# MJL 9/10 Added retry code in case write failed.
for { set rsp "Bad" } { $rsp == "Bad" } { } {
set potname [ format "%s%d" $potxy $potnumber ]
# MJL It seems that the pots can somehow get set to '65'. I believe this might be returned when the read
# is invalid (e.g. perhaps the read query is corrupted, then the pot index is out of range and the controller
# responds with '65' to let us know that). So it happened that some read pot values appeared to be '65'.
# But if the sct_dhv transact ever attempts to send '65' to a pot, it seems that it hangs forever.
# Another problem in the driver... Just limit the value to 0 - 63 as it should be
if { $potvalue < 0 } { set potvalue 0 }
if { $potvalue > 63 } { set potvalue 63 }
#clientput "About to transact: " $potname " " $potvalue
set rsp [ sct_dhv transact "p $potname $potvalue" ]
# MJL sometimes the driver returns absolute bollocks, looks like strings from inside the TCL interpreter.
# Under this condition, assume the write failed, although we can't really tell without reading back value, but don't bother.
# Just flag anything that's not 'ACK' as 'Bad' i.e. do retries.
# clientput "Response:" $rsp
if { $rsp != "ACK" } { set rsp "Bad" }
}
return $rsp
}
Publish ord_set_pot User
@@ -133,6 +160,27 @@ proc ord_load_pot_all { filename } {
}
Publish ord_load_pot_all User
proc ord_load_pot_all_old_format { filename } {
# When saved by the 21000N software, the first row is y in reversed order and the second row is x in normal order
# This routine reads the file, then reorders the values to normal x then y order
ord_load_pot_all $filename
global ord_pot_all_x
global ord_pot_all_y
set ord_pot_all_x_old_format $ord_pot_all_x
set ord_pot_all_y_old_format $ord_pot_all_y
set ord_pot_all_x ""
set ord_pot_all_y ""
for { set ixy 0 } { $ixy <= 191 } { incr ixy } {
lappend ord_pot_all_x [lindex $ord_pot_all_y_old_format $ixy]
lappend ord_pot_all_y [lindex $ord_pot_all_x_old_format [expr 191 - $ixy]]
}
clientput " All pot settings reordered from 21000N format to normal format."
clientput "x settings:" $ord_pot_all_x
clientput "y settings:" $ord_pot_all_y
}
Publish ord_load_pot_all_old_format User
set histogram_xy ""
set histogram_x ""
set histogram_y ""
@@ -157,7 +205,7 @@ proc ord_get_histogram_xy { bs_x_l bs_x_h bs_y_l bs_y_h roi_x_l roi_x_h roi_y_l
global histogram_x
global histogram_y
clientput "Retrieving 2D xy histogram..."
set histogram_xy [ lreplace [ split [ hmm get 1 ] ] 0 1 ]
set histogram_xy [ lreplace [ split [ ::histogram_memory::gethmm HISTOPERIOD_XY ] ] 0 1 ]
if { ($bs_x_l > $bs_x_h || $bs_y_l > $bs_y_h) && $roi_x_l == 0 && $roi_x_h == 191 && $roi_y_l == 0 && $roi_y_h == 191 } {
set get_full_histogram 1
clientput "Calculating 2D histograms over full detector area..."

View File

@@ -0,0 +1,17 @@
# Detector voltage controller
set sim_mode [SplitReply [detector_simulation]]
if {$::sim_mode == "true"} {
EvFactory new dhv1 sim
} else {
clientput "FastCom Detector Voltage control"
makeasyncqueue acq NHQ200 ca1-quokka 4002
evfactory new dhv1 nhq200 acq 1
dhv1 tolerance 5
dhv1 rate 10
dhv1 upper 2250
dhv1 lower 775
dhv1 max 2600
#dhv1 lock
}

View File

@@ -0,0 +1,33 @@
# Detector voltage controller
# Baud: 19200, Data bits: 8, Stop bits: 1, Parity: None, Flow: None, FIFO: Enable, Interface: RS485-4wire
fileeval $cfPath(hmm)/sct_orhvps_common.tcl
# Old Moxa (before 17/9/2010) in Quokka cabin
#::scobj::dethvps::init ca1-quokka 4001 4.1
#dhv1 max 2600
#dhv1 lower 19
#dhv1 upper 57
# New Moxa (after 17/9/2010) near Quokka tank
#::scobj::dethvps::init 137.157.202.86 4002 4.1
# Spare detector max voltage and pot values
#dhv1 max 2405
#dhv1 lower 19
#dhv1 upper 59
# 22/6/2011
set dhv1Max_SN006 2405
set upper_SN006 55
set dhv1Max_SN003 2600
set upper_SN003 57
set dhvMax $dhv1Max_SN006
set dhvUpper $upper_SN006
::scobj::dethvps::init 137.157.202.71 4001 [expr 0.1 * $dhvMax /63.0]
# Voltage = potval * (dhv1.max / 63)
# if potval = 60 and dhv1.max = 2400 then voltage = 60 * 2400/63 = 2285.7V
dhv1 max $dhvMax
dhv1 lower 19
dhv1 upper $dhvUpper

View File

@@ -4,7 +4,7 @@
::utility::mkVar FastShutter text manager FastShutter false instrument true false
# SET TO 1 TO USE THE TILT STAGE ie sample phi and chi
set use_tiltstage 0
set use_tiltstage 1
set animal quokka
set sim_mode [SplitReply [motor_simulation]]
@@ -51,16 +51,19 @@ set bs125sign -1
set bs34sign 1
#Measured absolute encoder reading at home position
set samchi_Home 7808328
set samphi_Home 7675008
set samchi_Home 538302
set samphi_Home 432405
set samx_Home 7420441
set samy_Home 7101486
set samz_Home 9944901
set samthet_Home 23004075
set det_Home 7055209
#set det_Home 8204259
#set det_Home 8204624
set det_Home 8204623
set detoff_Home 6857213
set srce_Home 7281463
# set srce_Home 7281463 ffr 30/1/2013: set new home=7282984 because enc val increased by 1521 after culvert job
set srce_Home 7282984
set apx_Home 12965422
set apz_Home 7500000
set att_Home 24782942
@@ -79,6 +82,10 @@ set bs_cntsPerX [expr 32768.0/360.0]
set bs_stepsPerX [expr -25000.0*160.0/360.0]
set pol_Home 7500000
set hez_Home 497988176
set hez_StepsPerX [expr -100.0 * 25000.0 / 14.0]
set hez_CntsPerX [expr 819200.0 / 14.0]
#HERE ARE THE LATEST VALUES
set pent_Home 8146159
# Guide Positions Mirrotron ffr 2009-07-18
@@ -185,19 +192,19 @@ Motor samchi $motor_driver_type [params \
port pmc1-quokka\
axis A\
units degrees\
hardlowerlim -20\
hardupperlim 20\
maxSpeed 1\
maxAccel 5\
maxDecel 5\
hardlowerlim -14.6\
hardupperlim 15\
maxSpeed 0.5\
maxAccel 0.25\
maxDecel 0.25\
stepsPerX 25000\
absEnc 1\
absEncHome $samchi_Home\
cntsPerX 8192]
samchi part sample
samchi long_name sample_chi
samchi softlowerlim -20
samchi softupperlim 20
samchi softlowerlim -14.6
samchi softupperlim 15
samchi home 0
# Sample tilt across beam [-20,+20] degrees
@@ -207,19 +214,19 @@ Motor samphi $motor_driver_type [params \
port pmc1-quokka\
axis B\
units degrees\
hardlowerlim -20\
hardupperlim 20\
maxSpeed 1\
maxAccel 5\
maxDecel 5\
stepsPerX 25000\
hardlowerlim -15\
hardupperlim 12\
maxSpeed 0.5\
maxAccel 0.25\
maxDecel 0.25\
stepsPerX -25000\
absEnc 1\
absEncHome $samphi_Home\
cntsPerX 8192]
cntsPerX -8192]
samphi part sample
samphi long_name sample_phi
samphi softlowerlim -20
samphi softupperlim 20
samphi softlowerlim -15
samphi softupperlim 11
samphi home 0
}
# Sample translation across beam [0,1000] mm
@@ -227,6 +234,7 @@ Motor samx $motor_driver_type [params \
asyncqueue mc1\
host mc1-quokka\
port pmc1-quokka\
action MC1\
axis C\
units mm\
hardlowerlim -500\
@@ -322,11 +330,14 @@ set det_StepsPerX [expr (25000.0*70.0)/377.0]
set det_CntsPerX [expr 8192.0/377.0]
# Detector translation along beam [0,20000] mm
# default hardlowerlim 488
# default det softlowerlim 510
# default hardupperlim 19320
# default det softupperlim 19250
Motor det $motor_driver_type [params \
asyncqueue mc1\
host mc1-quokka\
port pmc1-quokka\
action MC1\
axis G\
units mm\
hardlowerlim 488\
@@ -337,15 +348,20 @@ Motor det $motor_driver_type [params \
stepsPerX $det_StepsPerX\
absEnc 1\
absEncHome $det_Home\
cntsPerX $det_CntsPerX]
cntsPerX $det_CntsPerX\
nopowersave 1]
det backlash_offset 5
det part detector
det long_name detector_y
det precision 1
det softlowerlim 500
det softupperlim 19310
det home 350.5
det softlowerlim 510
det softupperlim 19250
det home 445
det speed 53
det Blockage_Fail 0
det Blockage_Check_Interval 5
det Blockage_Thresh 10
det Blockage_Ratio 1.1
det Blockage_Fail 1
# Detector translation across beam [-50,450] mm
# Looks like an non-metric screw pitch 0.2 inches / turn
@@ -690,8 +706,8 @@ srce long_name srce
srce home 180
srce softlowerlim -10
srce softupperlim 340
srce speed 1
srce precision 0.1
srce speed 1
srce posit_1 $srce_Home
srce posit_2 [expr $srce_Home - (1 * 5 * 8192)]
srce posit_3 [expr $srce_Home - (2 * 5 * 8192)]
@@ -774,6 +790,31 @@ att speed 5
att home -120
att precision 0.1
Motor hez $motor_driver_type [params \
asyncqueue mc3\
axis H\
units mm\
hardlowerlim 0\
hardupperlim 649\
maxSpeed 1.12\
maxAccel 0.5\
maxDecel 1\
stepsPerX $hez_StepsPerX\
absEnc 1\
absEncHome $hez_Home\
cntsPerX $hez_CntsPerX]
#hez backlash_offset 5
hez part collimator
hez long_name hez
hez precision 0.1
hez softlowerlim 1
hez softupperlim 648
hez home 0
hez speed 1
#hez Blockage_Check_Interval 5
#hez Blockage_Thresh 10
#hez Blockage_Ratio 1.1
#hez Blockage_Fail 1
############################
# Motor Controller 4
# Motor Controller 4
@@ -840,6 +881,7 @@ Motor bs1 $motor_driver_type [params \
absEnc 1\
absEncHome $bs1_Home\
cntsPerX $bs_cntsPerX]
bs1 Blockage_Thresh 1.0
bs1 part detector
bs1 long_name bs1
bs1 softlowerlim 11
@@ -860,6 +902,7 @@ Motor bs2 $motor_driver_type [params \
absEnc 1\
absEncHome $bs2_Home\
cntsPerX $bs_cntsPerX]
bs2 Blockage_Thresh 1.0
bs2 part detector
bs2 long_name bs2
bs2 softlowerlim 7
@@ -880,6 +923,7 @@ Motor bs3 $motor_driver_type [params \
absEnc 1\
absEncHome $bs3_Home\
cntsPerX $bs_cntsPerX]
bs3 Blockage_Thresh 1.0
bs3 part detector
bs3 long_name bs3
bs3 softlowerlim 11
@@ -900,6 +944,7 @@ Motor bs4 $motor_driver_type [params \
absEnc 1\
absEncHome $bs4_Home\
cntsPerX $bs_cntsPerX]
bs4 Blockage_Thresh 1.0
bs4 part detector
bs4 long_name bs4
bs4 softlowerlim 7
@@ -920,6 +965,7 @@ Motor bs5 $motor_driver_type [params \
absEnc 1\
absEncHome $bs5_Home\
cntsPerX $bs_cntsPerX]
bs5 Blockage_Thresh 1.0
bs5 part detector
bs5 long_name bs5
bs5 softlowerlim 11
@@ -940,6 +986,7 @@ Motor bs6 $motor_driver_type [params \
absEnc 1\
absEncHome $bs6_Home\
cntsPerX $bs_cntsPerX]
bs6 Blockage_Thresh 1.0
bs6 part detector
bs6 long_name bs6
bs6 softlowerlim 7

View File

@@ -35,16 +35,16 @@ set 20sample_table {
}
set 10sample_table {
1 453.7
2 411.7
3 369.7
4 327.7
5 285.7
6 203.7
7 161.7
8 119.7
9 77.7
10 35.7
1 203.40042
2 161.40042
3 119.40042
4 77.40042
5 35.40042
6 -46.5996
7 -88.5996
8 -130.5996
9 -172.5996
10 -214.5996
}
mkPosit sct_mc1 sampleNum float samx sample $20sample_table

View File

@@ -1,6 +1,6 @@
set sim_mode [SplitReply [plc_simulation]]
if {$sim_mode == "false"} {
MakeAsyncQueue plc_chan SafetyPLC 137.157.204.79 31001
MakeAsyncQueue plc_chan SafetyPLC 137.157.211.22 30001
MakeSafetyPLC plc plc_chan 0
}

View File

@@ -208,7 +208,8 @@ proc rdPwdAck {} {
set speedvar [expr 0.2*$rspeed/100]
if {[hval $root/status] == "busy"} {
set target [hgetpropval $root/setspeed target]
if {$rspeed != $target} {
# rspeed doesn't always match the speed you sent, eg If you send 15922 the velsel says it got 15923
if {[expr abs($rspeed - $target)] > 1} {
hset $root/device_error "Resending target speed $target"
hset $root/setspeed $target"
return idle
@@ -459,7 +460,7 @@ proc halt {root} {
set fmtspeed [format "%5d" $speed]
sct send "N#SOS#SPEED $fmtspeed"
sct target $lambda
hsetprop $vs_root/setspeed target $speed
hsetprop $vs_root/setspeed target $fmtspeed
hset $vs_root/status "busy"
statemon start nvs_speed
statemon start nvs_lambda

View File

@@ -5,6 +5,21 @@ namespace eval ::scobj::velocity_selector {
variable blocked_speeds
variable velsel_IP
variable velsel_port
variable nvs40Par
variable nvs43Par
variable velsel_ID
set nvs40Par(m_dTwistAngle) 48.30
set nvs40Par(m_dLength) 0.250
set nvs40Par(m_iMaxSpeed) 28300.0
set nvs40Par(rBeamCenter) 0.1100
set nvs40Par(VNeutron) 3955.98
set nvs43Par(m_dTwistAngle) 37.6
set nvs43Par(m_dLength) 0.250
set nvs43Par(m_iMaxSpeed) 21000.0
set nvs43Par(rBeamCenter) 0.1100
set nvs43Par(VNeutron) 3955.98
# Set configuration parameters for either the NVS40 or NVS43 velocity selector
set ::currVelSel [string tolower $::currVelSel]
@@ -13,11 +28,6 @@ namespace eval ::scobj::velocity_selector {
set velsel_ID "NVS40"
set velsel_IP "137.157.202.73"
set velsel_port 10000
set m_dTwistAngle 48.30
set m_dLength 0.250
set m_iMaxSpeed 28300.0
set rBeamCenter 0.1100
set VNeutron 3955.98
set ::scobj::velocity_selector::UID "NVS"
set ::scobj::velocity_selector::PWD "NVS"
set ::scobj::velocity_selector::blocked_speeds {
@@ -32,11 +42,6 @@ namespace eval ::scobj::velocity_selector {
set velsel_ID "NVS43"
set velsel_IP "137.157.202.74"
set velsel_port 10000
set m_dTwistAngle 37.6
set m_dLength 0.250
set m_iMaxSpeed 21000.0
set rBeamCenter 0.1100
set VNeutron 3955.98
set ::scobj::velocity_selector::UID "NVS"
set ::scobj::velocity_selector::PWD "NVS"
set ::scobj::velocity_selector::blocked_speeds {

View File

@@ -35,9 +35,12 @@ fileeval $cfPath(commands)/commands.tcl
fileeval $cfPath(anticollider)/anticollider.tcl
fileeval $cfPath(environment)/temperature/sct_julabo_lh45.tcl
fileeval $cfPath(environment)/temperature/sct_qlink.tcl
fileeval $cfPath(environment)/temperature/sct_watlow_st4.tcl
fileeval $cfPath(environment)/temperature/sct_rvasm2.tcl
#fileeval $cfPath(environment)/magneticField/sct_oxford_ips.tcl
fileeval $cfPath(environment)/temperature/sct_oxford_itc.tcl
fileeval $cfPath(environment)/magneticField/oxford_labview.tcl
fileeval $cfPath(environment)/magneticField/sct_bruker_BEC1.tcl
fileeval $cfPath(environment)/environment.tcl
fileeval $cfPath(environment)/sct_rheometer.tcl
fileeval $cfPath(environment)/sct_protek_common.tcl

View File

@@ -226,7 +226,6 @@ proc server_set_sobj_attributes {} {
::nexus::set_sobj_attributes
::histogram_memory::set_sobj_attributes
::utility::set_chopper_attributes
::utility::set_sctobj_attributes
::utility::set_sct_object_attributes
## TODO move the following to the new ansto gumxml.tcl
sicslist setatt getgumtreexml privilege internal

View File

@@ -435,12 +435,6 @@ proc ::utility::set_histomem_attributes {} {
sicslist setatt $hm mutable true
}
}
proc ::utility::set_sctobj_attributes {} {
foreach sobj [sicslist type SctController] {
hsetprop /$sobj control false
hsetprop /$sobj data false
}
}
proc ::utility::set_sct_object_attributes {} {
foreach sobj [sicslist type SCT_OBJECT] {
sicslist setatt $sobj data true

View File

@@ -40,6 +40,8 @@
#define DECADIC_CREEP (10)
#define SPEED_ON_MOVE 1
extern double DoubleTime(void);
/** \brief Used to ensure that the getDMCSetting function is called
* with valid values.
* \see getDMCSetting
@@ -181,7 +183,8 @@ struct __MoDriv {
double lastPosition; /**< Position at last position check */
int lastSteps;
int lastCounts;
double origPosition; /**< Position at last position check */
double origPosition; /**< Position at motor start */
double origTime; /**< Time at motor start */
int origSteps;
int origCounts;
double minRatio;
@@ -1972,7 +1975,9 @@ static void DMCState_Idle(pDMC2280Driv self, pEvtEvent event) {
}
return;
case CMD_HALT:
/* we are already halted so just reset run_flag*/
/* we are already halted so just reset driver_status and run_flag*/
if (self->driver_status == HWBusy)
self->driver_status = HWIdle;
self->run_flag = 0;
return;
}
@@ -2232,6 +2237,7 @@ static void DMCState_MotorOn(pDMC2280Driv self, pEvtEvent event) {
cmdPosition(self, absolute);
self->subState = 2;
/* save pre-motion values for logging */
self->origTime = DoubleTime();
self->origPosition = self->currPosition;
self->origCounts = self->currCounts;
self->origSteps = self->currSteps;
@@ -2549,17 +2555,19 @@ static void DMCState_Moving(pDMC2280Driv self, pEvtEvent event) {
double units = self->currPosition - self->origPosition;
long int steps = self->currSteps - self->origSteps;
long int counts = self->currCounts - self->origCounts;
double time = DoubleTime() - self->origTime;
char line[CMDLEN];
snprintf(line, CMDLEN, "Motor=%s stopped: units=%.6f,"
" steps=%ld, counts=%ld, stepsPerX=%.6f,"
" minRatio=%.6f, maxRatio=%.6f",
" ratio=(%.6f-%.6f), time=%.3f",
self->name,
units,
steps,
counts,
(double) steps / units,
self->minRatio,
self->maxRatio);
self->maxRatio,
time);
SICSLogWrite(line, eStatus);
}
change_state(self, DMCState_OffTimer);

View File

@@ -13,6 +13,7 @@
-----------------------------------------------------------------------*/
#include <stdlib.h>
#include <assert.h>
#include <glob.h>
#include <fortify.h>
#include <sics.h>
#include <motor.h>
@@ -24,6 +25,8 @@
#include "protocol.h"
#include "sicslist.h"
#include "macro.h"
#include "status.h"
/* site-specific driver header files */
#include "motor_dmc2280.h"
#include "motor_asim.h"
@@ -102,6 +105,72 @@ int SICS_Revision(SConnection *pCon, SicsInterp *pSics, void *pData, int argc, c
return OKOK;
};
void SiteReportVersion(void)
{
fprintf(stdout, "SICS version=%s revision=%s at %s\n",
SICS_VERSION, SICS_REVISION, SICS_SITE);
}
static int MacroFileEvalGlob(SConnection * pCon, SicsInterp * pInter, void *pData,
int argc, char *argv[])
{
int i;
int rv;
int flags;
Status eOld;
glob_t globbuf;
char *args[3];
assert(pCon);
assert(pInter);
/* check authorisation: only users permitted here */
if (!SCMatchRights(pCon, usUser)) {
SCWrite(pCon, "ERROR: Insufficient Privilege to do FileEval", eError);
return 0;
}
/* check enough arguments */
if (argc < 2) {
SCWrite(pCon, "ERROR: No filename specified ", eError);
return 0;
}
/* handle status first */
eOld = GetStatus();
SetStatus(eBatch);
flags = GLOB_NOSORT;
#if defined(GLOB_BRACE)
flags |= GLOB_BRACE;
#endif
#if defined(GLOB_TILDE_CHECK)
flags |= GLOB_TILDE_CHECK;
#endif
memset(&globbuf, 0, sizeof(globbuf));
for (i = 1; i < argc; ++i) {
glob(argv[i], flags, NULL, &globbuf);
flags |= GLOB_APPEND;
}
args[0] = "fileeval";
args[2] = NULL;
rv = 1;
for (i = 0; i < (int) globbuf.gl_pathc; ++i) {
args[1] = globbuf.gl_pathv[i];
SCPrintf(pCon, eStatus, "fileeval %s", args[1]);
if (0 == MacroFileEval(pCon, pInter, pData, 2, args))
rv = 0;
}
if (0 == globbuf.gl_pathc) {
SCWrite(pCon, "ERROR: No file(s) found in FileEvalGlob", eError);
rv = 0;
}
globfree(&globbuf);
SetStatus(eOld);
if (1 == rv)
SCSendOK(pCon);
return rv;
}
void SiteInit(void) {
int NetWatchInit(void);
NetWatchInit();
@@ -151,6 +220,7 @@ static void AddCommands(SicsInterp *pInter)
AddCommand(pInter,"SICS_Version",SICS_Version,NULL,NULL);
AddCommand(pInter,"SICS_Revision",SICS_Revision,NULL,NULL);
AddCommand(pInter, "sicslist", SicsList, NULL, NULL);
AddCommand(pInter, "FileEvalGlob", MacroFileEvalGlob, NULL, NULL);
/*
* Tcl 8.5 has implemented the clock command in tcl rather then C.