Rename from secop to frappy
debian/ is still missing, will follow in next commit. Fixes: #4626 Change-Id: Ia87c28c1c75b8402eedbfca47f888585a7881f44
This commit is contained in:

committed by
Enrico Faulhaber

parent
c1eb764b09
commit
7f166a5b8c
0
frappy_psi/__init__.py
Normal file
0
frappy_psi/__init__.py
Normal file
93
frappy_psi/ah2700.py
Normal file
93
frappy_psi/ah2700.py
Normal file
@ -0,0 +1,93 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""Andeen Hagerling capacitance bridge"""
|
||||
|
||||
from frappy.core import Done, FloatRange, HasIO, Parameter, Readable, StringIO, nopoll
|
||||
|
||||
|
||||
class Ah2700IO(StringIO):
|
||||
end_of_line = '\r\n'
|
||||
timeout = 5
|
||||
|
||||
|
||||
class Capacitance(HasIO, Readable):
|
||||
|
||||
value = Parameter('capacitance', FloatRange(unit='pF'))
|
||||
freq = Parameter('frequency', FloatRange(unit='Hz'), readonly=False, default=0)
|
||||
voltage = Parameter('voltage', FloatRange(unit='V'), readonly=False, default=0)
|
||||
loss = Parameter('loss', FloatRange(unit='deg'), default=0)
|
||||
|
||||
ioClass = Ah2700IO
|
||||
|
||||
def parse_reply(self, reply):
|
||||
if reply.startswith('SI'): # this is an echo
|
||||
self.communicate('SERIAL ECHO OFF')
|
||||
reply = self.communicate('SI')
|
||||
if not reply.startswith('F='): # this is probably an error message like "LOSS TOO HIGH"
|
||||
self.status = [self.Status.ERROR, reply]
|
||||
return
|
||||
self.status = [self.Status.IDLE, '']
|
||||
# examples of replies:
|
||||
# 'F= 1000.0 HZ C= 0.000001 PF L> 0.0 DS V= 15.0 V'
|
||||
# 'F= 1000.0 HZ C= 0.0000059 PF L=-0.4 DS V= 15.0 V OVEN'
|
||||
# 'LOSS TOO HIGH'
|
||||
# make sure there is always a space after '=' and '>'
|
||||
# split() ignores multiple white space
|
||||
reply = reply.replace('=', '= ').replace('>', '> ').split()
|
||||
_, freq, _, _, cap, _, _, loss, lossunit, _, volt = reply[:11]
|
||||
self.freq = freq
|
||||
self.voltage = volt
|
||||
self.value = cap
|
||||
if lossunit == 'DS':
|
||||
self.loss = loss
|
||||
else: # the unit was wrong, we want DS = tan(delta), not NS = nanoSiemens
|
||||
reply = self.communicate('UN DS').split() # UN DS returns a reply similar to SI
|
||||
try:
|
||||
self.loss = reply[7]
|
||||
except IndexError:
|
||||
pass # don't worry, loss will be updated next time
|
||||
|
||||
def read_value(self):
|
||||
self.parse_reply(self.communicate('SI')) # SI = single trigger
|
||||
return Done
|
||||
|
||||
@nopoll
|
||||
def read_freq(self):
|
||||
self.read_value()
|
||||
return Done
|
||||
|
||||
@nopoll
|
||||
def read_loss(self):
|
||||
self.read_value()
|
||||
return Done
|
||||
|
||||
@nopoll
|
||||
def read_voltage(self):
|
||||
self.read_value()
|
||||
return Done
|
||||
|
||||
def write_freq(self, value):
|
||||
self.parse_reply(self.communicate('FR %g;SI' % value))
|
||||
return Done
|
||||
|
||||
def write_voltage(self, value):
|
||||
self.parse_reply(self.communicate('V %g;SI' % value))
|
||||
return Done
|
99
frappy_psi/ccu4.py
Normal file
99
frappy_psi/ccu4.py
Normal file
@ -0,0 +1,99 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
#
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
#
|
||||
# *****************************************************************************
|
||||
|
||||
"""drivers for CCU4, the cryostat control unit at SINQ"""
|
||||
# the most common Frappy classes can be imported from frappy.core
|
||||
from frappy.core import EnumType, FloatRange, \
|
||||
HasIO, Parameter, Readable, StringIO
|
||||
|
||||
|
||||
class CCU4IO(StringIO):
|
||||
"""communication with CCU4"""
|
||||
# for completeness: (not needed, as it is the default)
|
||||
end_of_line = '\n'
|
||||
# on connect, we send 'cid' and expect a reply starting with 'CCU4'
|
||||
identification = [('cid', r'CCU4.*')]
|
||||
|
||||
|
||||
# inheriting HasIO allows us to use the communicate method for talking with the hardware
|
||||
# Readable as a base class defines the value and status parameters
|
||||
class HeLevel(HasIO, Readable):
|
||||
"""He Level channel of CCU4"""
|
||||
|
||||
# define the communication class to create the IO module
|
||||
ioClass = CCU4IO
|
||||
|
||||
# define or alter the parameters
|
||||
# as Readable.value exists already, we give only the modified property 'unit'
|
||||
value = Parameter(unit='%')
|
||||
empty_length = Parameter('warm length when empty', FloatRange(0, 2000, unit='mm'),
|
||||
readonly=False)
|
||||
full_length = Parameter('warm length when full', FloatRange(0, 2000, unit='mm'),
|
||||
readonly=False)
|
||||
sample_rate = Parameter('sample rate', EnumType(slow=0, fast=1), readonly=False)
|
||||
|
||||
Status = Readable.Status
|
||||
|
||||
# conversion of the code from the CCU4 parameter 'hsf'
|
||||
STATUS_MAP = {
|
||||
0: (Status.IDLE, 'sensor ok'),
|
||||
1: (Status.ERROR, 'sensor warm'),
|
||||
2: (Status.ERROR, 'no sensor'),
|
||||
3: (Status.ERROR, 'timeout'),
|
||||
4: (Status.ERROR, 'not yet read'),
|
||||
5: (Status.DISABLED, 'disabled'),
|
||||
}
|
||||
|
||||
def query(self, cmd):
|
||||
"""send a query and get the response
|
||||
|
||||
:param cmd: the name of the parameter to query or '<parameter>=<value'
|
||||
for changing a parameter
|
||||
:returns: the (new) value of the parameter
|
||||
"""
|
||||
name, txtvalue = self.communicate(cmd).split('=')
|
||||
assert name == cmd.split('=')[0] # check that we got a reply to our command
|
||||
return float(txtvalue)
|
||||
|
||||
def read_value(self):
|
||||
return self.query('h')
|
||||
|
||||
def read_status(self):
|
||||
return self.STATUS_MAP[int(self.query('hsf'))]
|
||||
|
||||
def read_empty_length(self):
|
||||
return self.query('hem')
|
||||
|
||||
def write_empty_length(self, value):
|
||||
return self.query('hem=%g' % value)
|
||||
|
||||
def read_full_length(self):
|
||||
return self.query('hfu')
|
||||
|
||||
def write_full_length(self, value):
|
||||
return self.query('hfu=%g' % value)
|
||||
|
||||
def read_sample_rate(self):
|
||||
return self.query('hf')
|
||||
|
||||
def write_sample_rate(self, value):
|
||||
return self.query('hf=%d' % value)
|
179
frappy_psi/channelswitcher.py
Normal file
179
frappy_psi/channelswitcher.py
Normal file
@ -0,0 +1,179 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""channel switcher Mixin
|
||||
|
||||
Example Config File:
|
||||
|
||||
[sw]
|
||||
description=the switcher for blabla channels
|
||||
class=frappy_facility.module.YourChannelSwitcher
|
||||
uri=...
|
||||
|
||||
[chan1]
|
||||
description=channel 1
|
||||
class=frappy_facility.module.YourChannel
|
||||
switcher=sw
|
||||
|
||||
[chan2]
|
||||
...
|
||||
"""
|
||||
|
||||
import time
|
||||
|
||||
from frappy.datatypes import IntRange, BoolType, FloatRange
|
||||
from frappy.core import Attached, Property, Drivable, Parameter, Readable, Done
|
||||
|
||||
|
||||
class ChannelSwitcher(Drivable):
|
||||
"""base class for the channel switcher
|
||||
|
||||
minimum implementation:
|
||||
- override :meth:`set_active_channel`
|
||||
|
||||
- <channel>.read_value() and <channel>.read_status() is called periodically
|
||||
every <channel>.pollinterval on the active channel only
|
||||
- <channel>.is_switching(...) is called every <switcher>.pollinterval
|
||||
during switching period, until it is returning False
|
||||
"""
|
||||
value = Parameter('the current channel number', IntRange(), needscfg=False)
|
||||
target = Parameter('channel to select', IntRange(), needscfg=False)
|
||||
autoscan = Parameter('whether to scan automatically',
|
||||
BoolType(), readonly=False, default=True)
|
||||
pollinterval = Parameter(default=1, export=False)
|
||||
switch_delay = Parameter('the time needed to switch between channels',
|
||||
FloatRange(0, None), readonly=False, default=5)
|
||||
measure_delay = Parameter('the time for staying at a channel',
|
||||
FloatRange(0, None), readonly=False, default=2)
|
||||
|
||||
fast_poll = 0.1
|
||||
_channels = None # dict <channel no> of <module object>
|
||||
_start_measure = 0
|
||||
_last_measure = 0
|
||||
_start_switch = 0
|
||||
_time_tol = 0.5
|
||||
|
||||
def earlyInit(self):
|
||||
super().earlyInit()
|
||||
self._channels = {}
|
||||
|
||||
def register_channel(self, mod):
|
||||
"""register module"""
|
||||
self._channels[mod.channel] = mod
|
||||
|
||||
def set_active_channel(self, chan):
|
||||
"""tell the HW the active channel
|
||||
|
||||
:param chan: a channel object
|
||||
|
||||
to be implemented
|
||||
"""
|
||||
raise NotImplementedError
|
||||
|
||||
def next_channel(self, channelno):
|
||||
next_channel = channelno
|
||||
first_channel = None
|
||||
for ch, mod in self._channels.items():
|
||||
if mod.enabled:
|
||||
if first_channel is None:
|
||||
first_channel = ch
|
||||
if next_channel == ch:
|
||||
next_channel = None
|
||||
elif next_channel is None:
|
||||
next_channel = ch
|
||||
break
|
||||
else:
|
||||
next_channel = first_channel
|
||||
return next_channel
|
||||
|
||||
def read_status(self):
|
||||
now = time.monotonic()
|
||||
if self.status[0] == 'BUSY':
|
||||
chan = self._channels[self.target]
|
||||
if chan.is_switching(now, self._start_switch, self.switch_delay):
|
||||
return Done
|
||||
self.setFastPoll(False)
|
||||
self.status = 'IDLE', 'measure'
|
||||
self.value = self.target
|
||||
self._start_measure = self._last_measure = now
|
||||
chan.read_value()
|
||||
chan.read_status()
|
||||
if self.measure_delay > self._time_tol:
|
||||
return Done
|
||||
else:
|
||||
chan = self._channels[self.value]
|
||||
self.read_value() # this might modify autoscan or deadline!
|
||||
if chan.enabled:
|
||||
if self.target != self.value: # may happen after startup
|
||||
self.target = self.value
|
||||
next_measure = self._last_measure + chan.pollinterval
|
||||
if now + self._time_tol > next_measure:
|
||||
chan.read_value()
|
||||
chan.read_status()
|
||||
self._last_measure = next_measure
|
||||
if not self.autoscan or now + self._time_tol < self._start_measure + self.measure_delay:
|
||||
return Done
|
||||
next_channel = self.next_channel(self.value)
|
||||
if next_channel == self.value:
|
||||
return 'IDLE', 'single channel'
|
||||
if next_channel is None:
|
||||
return 'ERROR', 'no enabled channel'
|
||||
self.write_target(next_channel)
|
||||
return self.status
|
||||
|
||||
def write_pollinterval(self, value):
|
||||
self._time_tol = min(1, value) * 0.5
|
||||
return value
|
||||
|
||||
def write_target(self, channel):
|
||||
if channel not in self._channels:
|
||||
raise ValueError('%r is no valid channel' % channel)
|
||||
if channel == self.target and self._channels[channel].enabled:
|
||||
return channel
|
||||
chan = self._channels[channel]
|
||||
chan.enabled = True
|
||||
self.set_active_channel(chan)
|
||||
self._start_switch = time.monotonic()
|
||||
self.status = 'BUSY', 'change channel'
|
||||
self.setFastPoll(True, self.fast_poll)
|
||||
return channel
|
||||
|
||||
|
||||
class Channel(Readable):
|
||||
"""base class for channels
|
||||
|
||||
you should override the datatype of the channel property,
|
||||
in order to match the datatype of the switchers value
|
||||
"""
|
||||
switcher = Attached()
|
||||
channel = Property('channel number', IntRange())
|
||||
enabled = Parameter('enabled flag', BoolType(), default=True)
|
||||
value = Parameter(needscfg=False)
|
||||
|
||||
def initModule(self):
|
||||
super().initModule()
|
||||
self.switcher.register_channel(self)
|
||||
|
||||
def doPoll(self):
|
||||
"""value and status are polled by switcher"""
|
||||
|
||||
def is_switching(self, now, last_switch, switch_delay):
|
||||
"""returns True when switching is done"""
|
||||
return now + self.switcher._time_tol < last_switch + switch_delay
|
172
frappy_psi/convergence.py
Normal file
172
frappy_psi/convergence.py
Normal file
@ -0,0 +1,172 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
#
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
#
|
||||
# *****************************************************************************
|
||||
|
||||
from frappy.core import Parameter, FloatRange, BUSY, IDLE, WARN
|
||||
from frappy.lib.statemachine import StateMachine, Retry, Stop
|
||||
|
||||
|
||||
class HasConvergence:
|
||||
"""mixin for convergence checks
|
||||
|
||||
Implementation based on tolerance, settling time and timeout.
|
||||
The algorithm does its best to support changes of these parameters on the
|
||||
fly. However, the full history is not considered, which means for example
|
||||
that the spent time inside tolerance stored already is not altered when
|
||||
changing tolerance.
|
||||
"""
|
||||
tolerance = Parameter('absolute tolerance', FloatRange(0, unit='$'), readonly=False, default=0)
|
||||
settling_time = Parameter(
|
||||
'''settling time
|
||||
|
||||
total amount of time the value has to be within tolerance before switching to idle.
|
||||
''', FloatRange(0, unit='sec'), readonly=False, default=60)
|
||||
timeout = Parameter(
|
||||
'''timeout
|
||||
|
||||
timeout = 0: disabled, else:
|
||||
A timeout event happens, when the difference abs(<target> - <value>) drags behind
|
||||
the expected difference for longer than <timeout>. The expected difference is determined
|
||||
by parameters 'workingramp' or 'ramp'. If ramp is not available, an exponential decay of
|
||||
the difference with <tolerance> as time constant is expected.
|
||||
As soon as the value is the first time within tolerance, the timeout criterium is changed:
|
||||
then the timeout event happens after this time + <settling_time> + <timeout>.
|
||||
''', FloatRange(0, unit='sec'), readonly=False, default=3600)
|
||||
status = Parameter('status determined from convergence checks', default=(IDLE, ''))
|
||||
convergence_state = None
|
||||
|
||||
def earlyInit(self):
|
||||
super().earlyInit()
|
||||
self.convergence_state = StateMachine(threaded=False, logger=self.log,
|
||||
cleanup=self.cleanup, spent_inside=0)
|
||||
|
||||
def cleanup(self, state):
|
||||
state.default_cleanup(state)
|
||||
if state.stopped:
|
||||
if state.stopped is Stop: # and not Restart
|
||||
self.status = WARN, 'stopped'
|
||||
else:
|
||||
self.status = WARN, repr(state.last_error)
|
||||
|
||||
def doPoll(self):
|
||||
super().doPoll()
|
||||
state = self.convergence_state
|
||||
state.cycle()
|
||||
|
||||
def get_min_slope(self, dif):
|
||||
slope = getattr(self, 'workingramp', 0) or getattr(self, 'ramp', 0)
|
||||
if slope or not self.timeout:
|
||||
return slope
|
||||
return dif / self.timeout # assume exponential decay of dif, with time constant <tolerance>
|
||||
|
||||
def get_dif_tol(self):
|
||||
value = self.read_value()
|
||||
tol = self.tolerance
|
||||
if not tol:
|
||||
tol = 0.01 * max(abs(self.target), abs(value))
|
||||
dif = abs(self.target - value)
|
||||
return dif, tol
|
||||
|
||||
def start_state(self):
|
||||
"""to be called from write_target"""
|
||||
self.convergence_state.start(self.state_approach)
|
||||
|
||||
def state_approach(self, state):
|
||||
"""approaching, checking progress (busy)"""
|
||||
state.spent_inside = 0
|
||||
dif, tol = self.get_dif_tol()
|
||||
if dif < tol:
|
||||
state.timeout_base = state.now
|
||||
return self.state_inside
|
||||
if not self.timeout:
|
||||
return Retry()
|
||||
if state.init:
|
||||
state.timeout_base = state.now
|
||||
state.dif_crit = dif # criterium for resetting timeout base
|
||||
self.status = BUSY, 'approaching'
|
||||
state.dif_crit -= self.get_min_slope(dif) * state.delta()
|
||||
if dif < state.dif_crit: # progress is good: reset timeout base
|
||||
state.timeout_base = state.now
|
||||
elif state.now > state.timeout_base + self.timeout:
|
||||
self.status = WARN, 'convergence timeout'
|
||||
return self.state_instable
|
||||
return Retry()
|
||||
|
||||
def state_inside(self, state):
|
||||
"""inside tolerance, still busy"""
|
||||
dif, tol = self.get_dif_tol()
|
||||
if dif > tol:
|
||||
return self.state_outside
|
||||
state.spent_inside += state.delta()
|
||||
if state.spent_inside > self.settling_time:
|
||||
self.status = IDLE, 'reached target'
|
||||
return self.state_stable
|
||||
if state.init:
|
||||
self.status = BUSY, 'inside tolerance'
|
||||
return Retry()
|
||||
|
||||
def state_outside(self, state):
|
||||
"""temporarely outside tolerance, busy"""
|
||||
dif, tol = self.get_dif_tol()
|
||||
if dif < tol:
|
||||
return self.state_inside
|
||||
if state.now > state.timeout_base + self.settling_time + self.timeout:
|
||||
self.status = WARN, 'settling timeout'
|
||||
return self.state_instable
|
||||
if state.init:
|
||||
self.status = BUSY, 'outside tolerance'
|
||||
# do not reset the settling time on occasional outliers, count backwards instead
|
||||
state.spent_inside = max(0.0, state.spent_inside - state.delta())
|
||||
return Retry()
|
||||
|
||||
def state_stable(self, state):
|
||||
"""stable, after settling_time spent within tolerance, idle"""
|
||||
dif, tol = self.get_dif_tol()
|
||||
if dif <= tol:
|
||||
return Retry()
|
||||
self.status = WARN, 'instable'
|
||||
state.spent_inside = max(self.settling_time, state.spent_inside)
|
||||
return self.state_instable
|
||||
|
||||
def state_instable(self, state):
|
||||
"""went outside tolerance from stable, warning"""
|
||||
dif, tol = self.get_dif_tol()
|
||||
if dif <= tol:
|
||||
state.spent_inside += state.delta()
|
||||
if state.spent_inside > self.settling_time:
|
||||
self.status = IDLE, 'stable' # = recovered from instable
|
||||
return self.state_stable
|
||||
else:
|
||||
state.spent_inside = max(0, state.spent_inside - state.delta())
|
||||
return Retry()
|
||||
|
||||
def state_interrupt(self, state):
|
||||
"""stopping"""
|
||||
self.status = IDLE, 'stopped' # stop called
|
||||
return self.state_instable
|
||||
|
||||
def stop(self):
|
||||
"""set to idle when busy
|
||||
|
||||
does not stop control!
|
||||
"""
|
||||
if self.isBusy():
|
||||
self.convergence_state.start(self.state_interrupt)
|
140
frappy_psi/historywriter.py
Normal file
140
frappy_psi/historywriter.py
Normal file
@ -0,0 +1,140 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
|
||||
import time
|
||||
import frappyhistory # pylint: disable=import-error
|
||||
from frappy.datatypes import get_datatype, IntRange, FloatRange, ScaledInteger,\
|
||||
EnumType, BoolType, StringType, TupleOf, StructOf
|
||||
|
||||
|
||||
def make_cvt_list(dt, tail=''):
|
||||
"""create conversion list
|
||||
|
||||
list of tuple (<conversion function>, <tail>, <curve options>)
|
||||
tail is a postfix to be appended in case of tuples and structs
|
||||
"""
|
||||
if isinstance(dt, (EnumType, IntRange, BoolType)):
|
||||
return[(int, tail, dict(type='NUM'))]
|
||||
if isinstance(dt, (FloatRange, ScaledInteger)):
|
||||
return [(dt.import_value, tail, dict(type='NUM', unit=dt.unit, period=5) if dt.unit else {})]
|
||||
if isinstance(dt, StringType):
|
||||
return [(lambda x: x, tail, dict(type='STR'))]
|
||||
if isinstance(dt, TupleOf):
|
||||
items = enumerate(dt.members)
|
||||
elif isinstance(dt, StructOf):
|
||||
items = dt.members.items()
|
||||
else:
|
||||
return [] # ArrayType, BlobType and TextType are ignored: too much data, probably not used
|
||||
result = []
|
||||
for subkey, elmtype in items:
|
||||
for fun, tail_, opts in make_cvt_list(elmtype, '%s.%s' % (tail, subkey)):
|
||||
result.append((lambda v, k=subkey, f=fun: f(v[k]), tail_, opts))
|
||||
return result
|
||||
|
||||
|
||||
class FrappyHistoryWriter(frappyhistory.FrappyWriter):
|
||||
"""extend writer to be used as an internal frappy connection
|
||||
|
||||
API of frappyhistory.FrappyWriter:
|
||||
|
||||
:meth:`put_def`(key, opts):
|
||||
|
||||
define or overwrite a new curve named <key> with options from dict <opts>
|
||||
options:
|
||||
|
||||
- type:
|
||||
'NUM' (any number) or 'STR' (text)
|
||||
remark: tuples and structs create multiple curves
|
||||
- period:
|
||||
the typical 'lifetime' of a value.
|
||||
The intention is, that points in a chart may be connected by a straight line
|
||||
when the distance is lower than this value. If not, the line should be drawn
|
||||
horizontally from the last point to a point <period> before the next value.
|
||||
For example a setpoint should have period 0, which will lead to a stepped
|
||||
line, whereas for a measured value like a temperature, period should be
|
||||
slightly bigger than the poll interval. In order to make full use of this,
|
||||
we would need some additional parameter property.
|
||||
- show: True/False, whether this curve should be shown or not by default in
|
||||
a summary chart
|
||||
- label: a label for the curve in the chart
|
||||
|
||||
:meth:`put`(timestamp, key, value)
|
||||
|
||||
timestamp: the timestamp. must not decrease!
|
||||
key: the curve name
|
||||
value: the value to be stored, converted to a string. '' indicates an undefined value
|
||||
|
||||
self.cache is a dict <key> of <value as string>, containing the last used value
|
||||
"""
|
||||
def __init__(self, directory, predefined_names, dispatcher):
|
||||
super().__init__(directory)
|
||||
self.predefined_names = predefined_names
|
||||
self.cvt_lists = {} # dict <mod:param> of <conversion list>
|
||||
self.activated = False
|
||||
self.dispatcher = dispatcher
|
||||
self._init_time = None
|
||||
|
||||
def init(self, msg):
|
||||
"""initialize from the 'describing' message"""
|
||||
action, _, description = msg
|
||||
assert action == 'describing'
|
||||
self._init_time = time.time()
|
||||
|
||||
for modname, moddesc in description['modules'].items():
|
||||
for pname, pdesc in moddesc['accessibles'].items():
|
||||
ident = key = modname + ':' + pname
|
||||
if pname.startswith('_') and pname[1:] not in self.predefined_names:
|
||||
key = modname + ':' + pname[1:]
|
||||
dt = get_datatype(pdesc['datainfo'])
|
||||
cvt_list = make_cvt_list(dt, key)
|
||||
for _, hkey, opts in cvt_list:
|
||||
if pname == 'value':
|
||||
opts['period'] = opts.get('period', 0)
|
||||
opts['show'] = True
|
||||
opts['label'] = modname
|
||||
elif pname == 'target':
|
||||
opts['period'] = 0
|
||||
opts['label'] = modname + '_target'
|
||||
opts['show'] = True
|
||||
self.put_def(hkey, opts)
|
||||
self.cvt_lists[ident] = cvt_list
|
||||
# self.put(self._init_time, 'STR', 'vars', ' '.join(vars))
|
||||
self.dispatcher.handle_activate(self, None, None)
|
||||
self._init_time = None
|
||||
|
||||
def send_reply(self, msg):
|
||||
action, ident, value = msg
|
||||
if not action.endswith('update'):
|
||||
print('unknown async message %r' % msg)
|
||||
return
|
||||
now = self._init_time or time.time() # on initialisation, use the same timestamp for all
|
||||
if action == 'update':
|
||||
for fun, key, _ in self.cvt_lists[ident]:
|
||||
# we only look at the value, qualifiers are ignored for now
|
||||
# we do not use the timestamp here, as a potentially decreasing value might
|
||||
# bring the reader software into trouble
|
||||
self.put(now, key, str(fun(value[0])))
|
||||
|
||||
else: # error_update
|
||||
for _, key, _ in self.cvt_lists[ident]:
|
||||
old = self.cache.get(key)
|
||||
if old is None:
|
||||
return # ignore if this key is not yet used
|
||||
self.put(now, key, '')
|
199
frappy_psi/k2601b.py
Normal file
199
frappy_psi/k2601b.py
Normal file
@ -0,0 +1,199 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""Keithley 2601B 4 quadrant source meter
|
||||
|
||||
* switching between voltage and current happens by setting their target
|
||||
* switching output off by setting the active parameter of the controlling
|
||||
module to False.
|
||||
* setting the active parameter to True raises an error
|
||||
"""
|
||||
|
||||
from frappy.core import Attached, BoolType, Done, EnumType, FloatRange, \
|
||||
HasIO, Module, Parameter, Readable, StringIO, Writable
|
||||
|
||||
|
||||
class K2601bIO(StringIO):
|
||||
identification = [('print(localnode.description)', 'Keithley Instruments SMU 2601B.*')]
|
||||
|
||||
|
||||
SOURCECMDS = {
|
||||
0: 'reset()'
|
||||
' smua.source.output = 0 print("ok")',
|
||||
1: 'reset()'
|
||||
' smua.source.func = smua.OUTPUT_DCAMPS'
|
||||
' display.smua.measure.func = display.MEASURE_DCVOLTS'
|
||||
' smua.source.autorangei = 1'
|
||||
' smua.source.output = 1 print("ok")',
|
||||
2: 'reset()'
|
||||
' smua.source.func = smua.OUTPUT_DCVOLTS'
|
||||
' display.smua.measure.func = display.MEASURE_DCAMPS'
|
||||
' smua.source.autorangev = 1'
|
||||
' smua.source.output = 1 print("ok")',
|
||||
}
|
||||
|
||||
|
||||
class SourceMeter(HasIO, Module):
|
||||
export = False # export for tests only
|
||||
mode = Parameter('measurement mode', EnumType(off=0, current=1, voltage=2),
|
||||
readonly=False, export=False)
|
||||
ilimit = Parameter('current limit', FloatRange(0, 2.0, unit='A'), default=2)
|
||||
vlimit = Parameter('voltage limit', FloatRange(0, 2.0, unit='V'), default=2)
|
||||
|
||||
ioClass = K2601bIO
|
||||
|
||||
def read_mode(self):
|
||||
return float(self.communicate('print((smua.source.func+1)*smua.source.output)'))
|
||||
|
||||
def write_mode(self, value):
|
||||
assert self.communicate(SOURCECMDS[value]) == 'ok'
|
||||
if value == 'current':
|
||||
self.write_vlimit(self.vlimit)
|
||||
elif value == 'voltage':
|
||||
self.write_ilimit(self.ilimit)
|
||||
return self.read_mode()
|
||||
|
||||
def read_ilimit(self):
|
||||
if self.mode == 'current':
|
||||
return self.ilimit
|
||||
return float(self.communicate('print(smua.source.limiti)'))
|
||||
|
||||
def write_ilimit(self, value):
|
||||
if self.mode == 'current':
|
||||
return self.ilimit
|
||||
return float(self.communicate('smua.source.limiti = %g print(smua.source.limiti)' % value))
|
||||
|
||||
def read_vlimit(self):
|
||||
if self.mode == 'voltage':
|
||||
return self.ilimit
|
||||
return float(self.communicate('print(smua.source.limitv)'))
|
||||
|
||||
def write_vlimit(self, value):
|
||||
if self.mode == 'voltage':
|
||||
return self.ilimit
|
||||
return float(self.communicate('smua.source.limitv = %g print(smua.source.limitv)' % value))
|
||||
|
||||
|
||||
class Power(HasIO, Readable):
|
||||
value = Parameter('readback power', FloatRange(unit='W'))
|
||||
ioClass = K2601bIO
|
||||
|
||||
def read_value(self):
|
||||
return float(self.communicate('print(smua.measure.p())'))
|
||||
|
||||
|
||||
class Resistivity(HasIO, Readable):
|
||||
value = Parameter('readback resistivity', FloatRange(unit='Ohm'))
|
||||
ioClass = K2601bIO
|
||||
|
||||
def read_value(self):
|
||||
return float(self.communicate('print(smua.measure.r())'))
|
||||
|
||||
|
||||
class Current(HasIO, Writable):
|
||||
sourcemeter = Attached()
|
||||
|
||||
value = Parameter('measured current', FloatRange(unit='A'))
|
||||
target = Parameter('set current', FloatRange(unit='A'))
|
||||
active = Parameter('current is controlled', BoolType(), default=False)
|
||||
limit = Parameter('current limit', FloatRange(0, 2.0, unit='A'), default=2)
|
||||
|
||||
def initModule(self):
|
||||
super().initModule()
|
||||
self.sourcemeter.registerCallbacks(self)
|
||||
|
||||
def read_value(self):
|
||||
return float(self.communicate('print(smua.measure.i())'))
|
||||
|
||||
def read_target(self):
|
||||
return float(self.communicate('print(smua.source.leveli)'))
|
||||
|
||||
def write_target(self, value):
|
||||
if value > self.sourcemeter.ilimit:
|
||||
raise ValueError('current exceeds limit')
|
||||
if not self.active:
|
||||
self.sourcemeter.write_mode('current') # triggers update_mode -> set active to True
|
||||
value = float(self.communicate('smua.source.leveli = %g print(smua.source.leveli)' % value))
|
||||
return value
|
||||
|
||||
def read_limit(self):
|
||||
return self.sourcemeter.read_ilimit()
|
||||
|
||||
def write_limit(self, value):
|
||||
return self.sourcemeter.write_ilimit(value)
|
||||
|
||||
def update_mode(self, mode):
|
||||
# will be called whenever the attached sourcemeters mode changes
|
||||
self.active = mode == 'current'
|
||||
|
||||
def write_active(self, value):
|
||||
self.sourcemeter.read_mode()
|
||||
if value == self.value:
|
||||
return Done
|
||||
if value:
|
||||
raise ValueError('activate only by setting target')
|
||||
self.sourcemeter.write_mode('off') # triggers update_mode -> set active to False
|
||||
return Done
|
||||
|
||||
|
||||
class Voltage(HasIO, Writable):
|
||||
sourcemeter = Attached()
|
||||
|
||||
value = Parameter('measured voltage', FloatRange(unit='V'))
|
||||
target = Parameter('set voltage', FloatRange(unit='V'))
|
||||
active = Parameter('voltage is controlled', BoolType())
|
||||
limit = Parameter('voltage limit', FloatRange(0, 2.0, unit='V'), default=2)
|
||||
|
||||
def initModule(self):
|
||||
super().initModule()
|
||||
self.sourcemeter.registerCallbacks(self)
|
||||
|
||||
def read_value(self):
|
||||
return float(self.communicate('print(smua.measure.v())'))
|
||||
|
||||
def read_target(self):
|
||||
return float(self.communicate('print(smua.source.levelv)'))
|
||||
|
||||
def write_target(self, value):
|
||||
if value > self.sourcemeter.vlimit:
|
||||
raise ValueError('voltage exceeds limit')
|
||||
if not self.active:
|
||||
self.sourcemeter.write_mode('voltage') # triggers update_mode -> set active to True
|
||||
value = float(self.communicate('smua.source.levelv = %g print(smua.source.levelv)' % value))
|
||||
return value
|
||||
|
||||
def read_limit(self):
|
||||
return self.sourcemeter.read_vlimit()
|
||||
|
||||
def write_limit(self, value):
|
||||
return self.sourcemeter.write_vlimit(value)
|
||||
|
||||
def update_mode(self, mode):
|
||||
# will be called whenever the attached sourcemeters mode changes
|
||||
self.active = mode == 'voltage'
|
||||
|
||||
def write_active(self, value):
|
||||
self.sourcemeter.read_mode()
|
||||
if value == self.value:
|
||||
return Done
|
||||
if value:
|
||||
raise ValueError('activate only by setting target')
|
||||
self.sourcemeter.write_mode('off') # triggers update_mode -> set active to False
|
||||
return Done
|
315
frappy_psi/ls370res.py
Normal file
315
frappy_psi/ls370res.py
Normal file
@ -0,0 +1,315 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""LakeShore Model 370 resistance channel
|
||||
|
||||
implements autoscan and autorange by software.
|
||||
when the autoscan or autorange button is pressed, the state is toggled,
|
||||
and the hardware mode switched off again.
|
||||
At startup, the configurable default mode is set, independent of
|
||||
the hardware state.
|
||||
"""
|
||||
|
||||
import time
|
||||
from ast import literal_eval
|
||||
|
||||
import frappy.io
|
||||
from frappy.datatypes import BoolType, EnumType, FloatRange, IntRange
|
||||
from frappy.lib import formatStatusBits
|
||||
from frappy.core import Done, Drivable, Parameter, Property, CommonReadHandler, CommonWriteHandler
|
||||
from frappy.io import HasIO
|
||||
from frappy_psi.channelswitcher import Channel, ChannelSwitcher
|
||||
|
||||
Status = Drivable.Status
|
||||
|
||||
|
||||
STATUS_BIT_LABELS = 'CS_OVL VCM_OVL VMIX_OVL VDIF_OVL R_OVER R_UNDER T_OVER T_UNDER'.split()
|
||||
|
||||
|
||||
class StringIO(frappy.io.StringIO):
|
||||
identification = [('*IDN?', 'LSCI,MODEL370,.*')]
|
||||
wait_before = 0.05
|
||||
|
||||
|
||||
class Switcher(HasIO, ChannelSwitcher):
|
||||
value = Parameter(datatype=IntRange(1, 16))
|
||||
target = Parameter(datatype=IntRange(1, 16))
|
||||
use_common_delays = Parameter('use switch_delay and measure_delay instead of the channels pause and dwell',
|
||||
BoolType(), readonly=False, default=False)
|
||||
common_pause = Parameter('pause with common delays', FloatRange(3, 200, unit='s'), readonly=False, default=3)
|
||||
ioClass = StringIO
|
||||
fast_poll = 1
|
||||
_measure_delay = None
|
||||
_switch_delay = None
|
||||
|
||||
def startModule(self, start_events):
|
||||
super().startModule(start_events)
|
||||
# disable unused channels
|
||||
for ch in range(1, 16):
|
||||
if ch not in self._channels:
|
||||
self.communicate('INSET %d,0,0,0,0,0;INSET?%d' % (ch, ch))
|
||||
channelno, autoscan = literal_eval(self.communicate('SCAN?'))
|
||||
if channelno in self._channels and self._channels[channelno].enabled:
|
||||
if not autoscan:
|
||||
return # nothing to do
|
||||
else:
|
||||
channelno = self.next_channel(channelno)
|
||||
if channelno is None:
|
||||
self.status = 'ERROR', 'no enabled channel'
|
||||
return
|
||||
self.communicate('SCAN %d,0;SCAN?' % channelno)
|
||||
|
||||
def doPoll(self):
|
||||
"""poll buttons
|
||||
|
||||
and check autorange during filter time
|
||||
"""
|
||||
super().doPoll()
|
||||
self._channels[self.target]._read_value() # check range or read
|
||||
channelno, autoscan = literal_eval(self.communicate('SCAN?'))
|
||||
if autoscan:
|
||||
# pressed autoscan button: switch off HW autoscan and toggle soft autoscan
|
||||
self.autoscan = not self.autoscan
|
||||
self.communicate('SCAN %d,0;SCAN?' % self.value)
|
||||
if channelno != self.value:
|
||||
# channel changed by keyboard, do not yet return new channel
|
||||
self.write_target(channelno)
|
||||
chan = self._channels.get(channelno)
|
||||
if chan is None:
|
||||
channelno = self.next_channel(channelno)
|
||||
if channelno is None:
|
||||
raise ValueError('no channels enabled')
|
||||
self.write_target(channelno)
|
||||
chan = self._channels.get(self.value)
|
||||
chan.read_autorange()
|
||||
chan.fix_autorange() # check for toggled autorange button
|
||||
return Done
|
||||
|
||||
def write_switch_delay(self, value):
|
||||
self._switch_delay = value
|
||||
return super().write_switch_delay(value)
|
||||
|
||||
def write_measure_delay(self, value):
|
||||
self._measure_delay = value
|
||||
return super().write_measure_delay(value)
|
||||
|
||||
def write_use_common_delays(self, value):
|
||||
if value:
|
||||
# use values from a previous change, instead of
|
||||
# the values from the current channel
|
||||
if self._measure_delay is not None:
|
||||
self.measure_delay = self._measure_delay
|
||||
if self._switch_delay is not None:
|
||||
self.switch_delay = self._switch_delay
|
||||
return value
|
||||
|
||||
def set_delays(self, chan):
|
||||
if self.use_common_delays:
|
||||
if chan.dwell != self.measure_delay:
|
||||
chan.write_dwell(self.measure_delay)
|
||||
if chan.pause != self.common_pause:
|
||||
chan.write_pause(self.common_pause)
|
||||
filter_ = max(0, self.switch_delay - self.common_pause)
|
||||
if chan.filter != filter_:
|
||||
chan.write_filter(filter_)
|
||||
else:
|
||||
# switch_delay and measure_delay is changing with channel
|
||||
self.switch_delay = chan.pause + chan.filter
|
||||
self.measure_delay = chan.dwell
|
||||
|
||||
def set_active_channel(self, chan):
|
||||
self.communicate('SCAN %d,0;SCAN?' % chan.channel)
|
||||
chan._last_range_change = time.monotonic()
|
||||
self.set_delays(chan)
|
||||
|
||||
|
||||
class ResChannel(Channel):
|
||||
"""temperature channel on Lakeshore 370"""
|
||||
|
||||
RES_RANGE = {key: i+1 for i, key in list(
|
||||
enumerate(mag % val for mag in ['%gmOhm', '%gOhm', '%gkOhm', '%gMOhm']
|
||||
for val in [2, 6.32, 20, 63.2, 200, 632]))[:-2]}
|
||||
CUR_RANGE = {key: i + 1 for i, key in list(
|
||||
enumerate(mag % val for mag in ['%gpA', '%gnA', '%guA', '%gmA']
|
||||
for val in [1, 3.16, 10, 31.6, 100, 316]))[:-2]}
|
||||
VOLT_RANGE = {key: i + 1 for i, key in list(
|
||||
enumerate(mag % val for mag in ['%guV', '%gmV']
|
||||
for val in [2, 6.32, 20, 63.2, 200, 632]))}
|
||||
RES_SCALE = [2 * 10 ** (0.5 * i) for i in range(-7, 16)] # RES_SCALE[0] is not used
|
||||
MAX_RNG = len(RES_SCALE) - 1
|
||||
|
||||
channel = Property('the Lakeshore channel', datatype=IntRange(1, 16), export=False)
|
||||
|
||||
value = Parameter(datatype=FloatRange(unit='Ohm'))
|
||||
pollinterval = Parameter(visibility=3, default=1)
|
||||
range = Parameter('reading range', readonly=False,
|
||||
datatype=EnumType(**RES_RANGE))
|
||||
minrange = Parameter('minimum range for software autorange', readonly=False, default=1,
|
||||
datatype=EnumType(**RES_RANGE))
|
||||
autorange = Parameter('autorange', datatype=BoolType(),
|
||||
readonly=False, default=1)
|
||||
iexc = Parameter('current excitation', datatype=EnumType(off=0, **CUR_RANGE), readonly=False)
|
||||
vexc = Parameter('voltage excitation', datatype=EnumType(off=0, **VOLT_RANGE), readonly=False)
|
||||
enabled = Parameter('is this channel enabled?', datatype=BoolType(), readonly=False)
|
||||
pause = Parameter('pause after channel change', datatype=FloatRange(3, 60, unit='s'), readonly=False)
|
||||
dwell = Parameter('dwell time with autoscan', datatype=FloatRange(1, 200, unit='s'), readonly=False)
|
||||
filter = Parameter('filter time', datatype=FloatRange(1, 200, unit='s'), readonly=False)
|
||||
|
||||
_toggle_autorange = 'init'
|
||||
_prev_rdgrng = (1, 1) # last read values for icur and exc
|
||||
_last_range_change = 0
|
||||
rdgrng_params = 'range', 'iexc', 'vexc'
|
||||
inset_params = 'enabled', 'pause', 'dwell'
|
||||
|
||||
def communicate(self, command):
|
||||
return self.switcher.communicate(command)
|
||||
|
||||
def read_status(self):
|
||||
if not self.enabled:
|
||||
return [self.Status.DISABLED, 'disabled']
|
||||
if not self.channel == self.switcher.value == self.switcher.target:
|
||||
return Done
|
||||
result = int(self.communicate('RDGST?%d' % self.channel))
|
||||
result &= 0x37 # mask T_OVER and T_UNDER (change this when implementing temperatures instead of resistivities)
|
||||
statustext = ' '.join(formatStatusBits(result, STATUS_BIT_LABELS))
|
||||
if statustext:
|
||||
return [self.Status.ERROR, statustext]
|
||||
return [self.Status.IDLE, '']
|
||||
|
||||
def _read_value(self):
|
||||
"""read value, without update"""
|
||||
now = time.monotonic()
|
||||
if now + 0.5 < max(self._last_range_change, self.switcher._start_switch) + self.pause:
|
||||
return None
|
||||
result = self.communicate('RDGR?%d' % self.channel)
|
||||
result = float(result)
|
||||
if self.autorange:
|
||||
self.fix_autorange()
|
||||
if now + 0.5 > self._last_range_change + self.pause:
|
||||
rng = int(max(self.minrange, self.range)) # convert from enum to int
|
||||
if self.status[1] == '':
|
||||
if abs(result) > self.RES_SCALE[rng]:
|
||||
if rng < 22:
|
||||
rng += 1
|
||||
else:
|
||||
lim = 0.2
|
||||
while rng > self.minrange and abs(result) < lim * self.RES_SCALE[rng]:
|
||||
rng -= 1
|
||||
lim -= 0.05 # not more than 4 steps at once
|
||||
# effectively: <0.16 %: 4 steps, <1%: 3 steps, <5%: 2 steps, <20%: 1 step
|
||||
elif rng < self.MAX_RNG:
|
||||
rng = min(self.MAX_RNG, rng + 1)
|
||||
if rng != self.range:
|
||||
self.write_range(rng)
|
||||
self._last_range_change = now
|
||||
return result
|
||||
|
||||
def read_value(self):
|
||||
if self.channel == self.switcher.value == self.switcher.target:
|
||||
return self._read_value()
|
||||
return Done # return previous value
|
||||
|
||||
def is_switching(self, now, last_switch, switch_delay):
|
||||
last_switch = max(last_switch, self._last_range_change)
|
||||
if now + 0.5 > last_switch + self.pause:
|
||||
self._read_value() # adjust range only
|
||||
return super().is_switching(now, last_switch, switch_delay)
|
||||
|
||||
@CommonReadHandler(rdgrng_params)
|
||||
def read_rdgrng(self):
|
||||
iscur, exc, rng, autorange, excoff = literal_eval(
|
||||
self.communicate('RDGRNG?%d' % self.channel))
|
||||
self._prev_rdgrng = iscur, exc
|
||||
if autorange: # pressed autorange button
|
||||
if not self._toggle_autorange:
|
||||
self._toggle_autorange = True
|
||||
iexc = 0 if excoff or not iscur else exc
|
||||
vexc = 0 if excoff or iscur else exc
|
||||
if (rng, iexc, vexc) != (self.range, self.iexc, self.vexc):
|
||||
self._last_range_change = time.monotonic()
|
||||
self.range, self.iexc, self.vexc = rng, iexc, vexc
|
||||
|
||||
@CommonWriteHandler(rdgrng_params)
|
||||
def write_rdgrng(self, change):
|
||||
self.read_range() # make sure autorange is handled
|
||||
if 'vexc' in change: # in case vext is changed, do not consider iexc
|
||||
change['iexc'] = 0
|
||||
if change['iexc'] != 0: # we need '!= 0' here, as bool(enum) is always True!
|
||||
iscur = 1
|
||||
exc = change['iexc']
|
||||
excoff = 0
|
||||
elif change['vexc'] != 0: # we need '!= 0' here, as bool(enum) is always True!
|
||||
iscur = 0
|
||||
exc = change['vexc']
|
||||
excoff = 0
|
||||
else:
|
||||
iscur, exc = self._prev_rdgrng # set to last read values
|
||||
excoff = 1
|
||||
rng = change['range']
|
||||
if self.autorange:
|
||||
if rng < self.minrange:
|
||||
rng = self.minrange
|
||||
self.communicate('RDGRNG %d,%d,%d,%d,%d,%d;*OPC?' % (
|
||||
self.channel, iscur, exc, rng, 0, excoff))
|
||||
self.read_range()
|
||||
|
||||
def fix_autorange(self):
|
||||
if self._toggle_autorange:
|
||||
if self._toggle_autorange == 'init':
|
||||
self.write_autorange(True)
|
||||
else:
|
||||
self.write_autorange(not self.autorange)
|
||||
self._toggle_autorange = False
|
||||
|
||||
@CommonReadHandler(inset_params)
|
||||
def read_inset(self):
|
||||
# ignore curve no and temperature coefficient
|
||||
enabled, dwell, pause, _, _ = literal_eval(
|
||||
self.communicate('INSET?%d' % self.channel))
|
||||
self.enabled = enabled
|
||||
self.dwell = dwell
|
||||
self.pause = pause
|
||||
|
||||
@CommonWriteHandler(inset_params)
|
||||
def write_inset(self, change):
|
||||
_, _, _, curve, tempco = literal_eval(
|
||||
self.communicate('INSET?%d' % self.channel))
|
||||
self.enabled, self.dwell, self.pause, _, _ = literal_eval(
|
||||
self.communicate('INSET %d,%d,%d,%d,%d,%d;INSET?%d' % (
|
||||
self.channel, change['enabled'], change['dwell'], change['pause'], curve, tempco,
|
||||
self.channel)))
|
||||
if 'enabled' in change and change['enabled']:
|
||||
# switch to enabled channel
|
||||
self.switcher.write_target(self.channel)
|
||||
elif self.switcher.target == self.channel:
|
||||
self.switcher.set_delays(self)
|
||||
|
||||
def read_filter(self):
|
||||
on, settle, _ = literal_eval(self.communicate('FILTER?%d' % self.channel))
|
||||
return settle if on else 0
|
||||
|
||||
def write_filter(self, value):
|
||||
on = 1 if value else 0
|
||||
value = max(1, value)
|
||||
on, settle, _ = literal_eval(self.communicate(
|
||||
'FILTER %d,%d,%g,80;FILTER?%d' % (self.channel, on, value, self.channel)))
|
||||
if not on:
|
||||
settle = 0
|
||||
return settle
|
75
frappy_psi/ls370sim.py
Normal file
75
frappy_psi/ls370sim.py
Normal file
@ -0,0 +1,75 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""a very simple simulator for a LakeShore Model 370"""
|
||||
|
||||
from frappy.modules import Communicator
|
||||
|
||||
|
||||
class Ls370Sim(Communicator):
|
||||
CHANNEL_COMMANDS = [
|
||||
('RDGR?%d', '1.0'),
|
||||
('RDGST?%d', '0'),
|
||||
('RDGRNG?%d', '0,5,5,0,0'),
|
||||
('INSET?%d', '1,5,5,0,0'),
|
||||
('FILTER?%d', '1,5,80'),
|
||||
]
|
||||
OTHER_COMMANDS = [
|
||||
('*IDN?', 'LSCI,MODEL370,370184,05302003'),
|
||||
('SCAN?', '3,1'),
|
||||
('*OPC?', '1'),
|
||||
]
|
||||
|
||||
def earlyInit(self):
|
||||
super().earlyInit()
|
||||
self._data = dict(self.OTHER_COMMANDS)
|
||||
for fmt, v in self.CHANNEL_COMMANDS:
|
||||
for chan in range(1,17):
|
||||
self._data[fmt % chan] = v
|
||||
|
||||
def communicate(self, command):
|
||||
self.comLog('> %s' % command)
|
||||
# simulation part, time independent
|
||||
for channel in range(1,17):
|
||||
_, _, _, _, excoff = self._data['RDGRNG?%d' % channel].split(',')
|
||||
if excoff == '1':
|
||||
self._data['RDGST?%d' % channel] = '6'
|
||||
else:
|
||||
self._data['RDGST?%d' % channel] = '0'
|
||||
|
||||
chunks = command.split(';')
|
||||
reply = []
|
||||
for chunk in chunks:
|
||||
if '?' in chunk:
|
||||
reply.append(self._data[chunk])
|
||||
else:
|
||||
for nqarg in (1,0):
|
||||
if nqarg == 0:
|
||||
qcmd, arg = chunk.split(' ', 1)
|
||||
qcmd += '?'
|
||||
else:
|
||||
qcmd, arg = chunk.split(',', nqarg)
|
||||
qcmd = qcmd.replace(' ', '?', 1)
|
||||
if qcmd in self._data:
|
||||
self._data[qcmd] = arg
|
||||
break
|
||||
reply = ';'.join(reply)
|
||||
self.comLog('< %s' % reply)
|
||||
return reply
|
543
frappy_psi/mercury.py
Normal file
543
frappy_psi/mercury.py
Normal file
@ -0,0 +1,543 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""oxford instruments mercury family"""
|
||||
|
||||
|
||||
import math
|
||||
import re
|
||||
import time
|
||||
|
||||
from frappy.core import Drivable, HasIO, Writable, \
|
||||
Parameter, Property, Readable, StringIO, Attached, Done, IDLE, nopoll
|
||||
from frappy.datatypes import EnumType, FloatRange, StringType, StructOf, BoolType
|
||||
from frappy.errors import HardwareError
|
||||
from frappy_psi.convergence import HasConvergence
|
||||
from frappy.lib.enum import Enum
|
||||
|
||||
|
||||
VALUE_UNIT = re.compile(r'(.*\d|inf)([A-Za-z/%]*)$')
|
||||
SELF = 0
|
||||
|
||||
|
||||
def as_float(value):
|
||||
if isinstance(value, str):
|
||||
return float(VALUE_UNIT.match(value).group(1))
|
||||
return '%g' % value
|
||||
|
||||
|
||||
def as_string(value):
|
||||
return value
|
||||
|
||||
|
||||
class Mapped:
|
||||
def __init__(self, **kwds):
|
||||
self.mapping = kwds
|
||||
self.mapping.update({v: k for k, v in kwds.items()})
|
||||
|
||||
def __call__(self, value):
|
||||
return self.mapping[value]
|
||||
|
||||
|
||||
off_on = Mapped(OFF=False, ON=True)
|
||||
fast_slow = Mapped(ON=0, OFF=1) # maps OIs slow=ON/fast=OFF to sample_rate.slow=0/sample_rate.fast=1
|
||||
|
||||
|
||||
class IO(StringIO):
|
||||
identification = [('*IDN?', r'IDN:OXFORD INSTRUMENTS:MERCURY*')]
|
||||
|
||||
|
||||
class MercuryChannel(HasIO):
|
||||
slot = Property('''slot uids
|
||||
|
||||
example: DB6.T1,DB1.H1
|
||||
slot ids for sensor (and control output)''',
|
||||
StringType())
|
||||
channel_name = Parameter('mercury nick name', StringType(), default='')
|
||||
channel_type = '' #: channel type(s) for sensor (and control) e.g. TEMP,HTR or PRES,AUX
|
||||
|
||||
def _complete_adr(self, adr):
|
||||
"""complete address from channel_type and slot"""
|
||||
head, sep, tail = adr.partition(':')
|
||||
for i, (channel_type, slot) in enumerate(zip(self.channel_type.split(','), self.slot.split(','))):
|
||||
if head == str(i):
|
||||
return 'DEV:%s:%s%s%s' % (slot, channel_type, sep, tail)
|
||||
if head == channel_type:
|
||||
return 'DEV:%s:%s%s%s' % (slot, head, sep, tail)
|
||||
return adr
|
||||
|
||||
def multiquery(self, adr, names=(), convert=as_float):
|
||||
"""get parameter(s) in mercury syntax
|
||||
|
||||
:param adr: the 'address part' of the SCPI command
|
||||
the DEV:<slot> is added automatically, when adr starts with the channel type
|
||||
in addition, when adr starts with '0:' or '1:', channel type and slot are added
|
||||
:param names: the SCPI names of the parameter(s), for example ['TEMP']
|
||||
:param convert: a converter function (converts replied string to value)
|
||||
:return: the values as tuple
|
||||
|
||||
Example:
|
||||
adr='AUX:SIG'
|
||||
names = ('PERC',)
|
||||
self.channel_type='PRES,AUX' # adr starts with 'AUX'
|
||||
self.slot='DB5.P1,DB3.G1' # -> take second slot
|
||||
-> query command will be READ:DEV:DB3.G1:PRES:SIG:PERC
|
||||
"""
|
||||
adr = self._complete_adr(adr)
|
||||
cmd = 'READ:%s:%s' % (adr, ':'.join(names))
|
||||
reply = self.communicate(cmd)
|
||||
head = 'STAT:%s:' % adr
|
||||
try:
|
||||
assert reply.startswith(head)
|
||||
replyiter = iter(reply[len(head):].split(':'))
|
||||
keys, result = zip(*zip(replyiter, replyiter))
|
||||
assert keys == tuple(names)
|
||||
return tuple(convert(r) for r in result)
|
||||
except (AssertionError, AttributeError, ValueError):
|
||||
raise HardwareError('invalid reply %r to cmd %r' % (reply, cmd)) from None
|
||||
|
||||
def multichange(self, adr, values, convert=as_float):
|
||||
"""set parameter(s) in mercury syntax
|
||||
|
||||
:param adr: as in see multiquery method
|
||||
:param values: [(name1, value1), (name2, value2) ...]
|
||||
:param convert: a converter function (converts given value to string and replied string to value)
|
||||
:return: the values as tuple
|
||||
|
||||
Example:
|
||||
adr='0:LOOP'
|
||||
values = [('P', 5), ('I', 2), ('D', 0)]
|
||||
self.channel_type='TEMP,HTR' # adr starts with 0: take TEMP
|
||||
self.slot='DB6.T1,DB1.H1' # and take first slot
|
||||
-> change command will be SET:DEV:DB6.T1:TEMP:LOOP:P:5:I:2:D:0
|
||||
"""
|
||||
adr = self._complete_adr(adr)
|
||||
params = ['%s:%s' % (k, convert(v)) for k, v in values]
|
||||
cmd = 'SET:%s:%s' % (adr, ':'.join(params))
|
||||
reply = self.communicate(cmd)
|
||||
head = 'STAT:SET:%s:' % adr
|
||||
|
||||
try:
|
||||
assert reply.startswith(head)
|
||||
replyiter = iter(reply[len(head):].split(':'))
|
||||
keys, result, valid = zip(*zip(replyiter, replyiter, replyiter))
|
||||
assert keys == tuple(k for k, _ in values)
|
||||
assert any(v == 'VALID' for v in valid)
|
||||
return tuple(convert(r) for r in result)
|
||||
except (AssertionError, AttributeError, ValueError) as e:
|
||||
raise HardwareError('invalid reply %r to cmd %r' % (reply, cmd)) from e
|
||||
|
||||
def query(self, adr, convert=as_float):
|
||||
"""query a single parameter
|
||||
|
||||
'adr' and 'convert' areg
|
||||
"""
|
||||
adr, _, name = adr.rpartition(':')
|
||||
return self.multiquery(adr, [name], convert)[0]
|
||||
|
||||
def change(self, adr, value, convert=as_float):
|
||||
adr, _, name = adr.rpartition(':')
|
||||
return self.multichange(adr, [(name, value)], convert)[0]
|
||||
|
||||
def read_channel_name(self):
|
||||
if self.channel_name:
|
||||
return Done # channel name will not change
|
||||
return self.query('0:NICK', as_string)
|
||||
|
||||
|
||||
class TemperatureSensor(MercuryChannel, Readable):
|
||||
channel_type = 'TEMP'
|
||||
value = Parameter(unit='K')
|
||||
raw = Parameter('raw value', FloatRange(unit='Ohm'))
|
||||
|
||||
def read_value(self):
|
||||
return self.query('TEMP:SIG:TEMP')
|
||||
|
||||
def read_raw(self):
|
||||
return self.query('TEMP:SIG:RES')
|
||||
|
||||
|
||||
class HasInput(MercuryChannel):
|
||||
controlled_by = Parameter('source of target value', EnumType(members={'self': SELF}), default=0)
|
||||
target = Parameter(readonly=False)
|
||||
input_modules = ()
|
||||
|
||||
def add_input(self, modobj):
|
||||
if not self.input_modules:
|
||||
self.input_modules = []
|
||||
self.input_modules.append(modobj)
|
||||
prev_enum = self.parameters['controlled_by'].datatype._enum
|
||||
# add enum member, using autoincrement feature of Enum
|
||||
self.parameters['controlled_by'].datatype = EnumType(Enum(prev_enum, **{modobj.name: None}))
|
||||
|
||||
def write_controlled_by(self, value):
|
||||
if self.controlled_by == value:
|
||||
return Done
|
||||
self.controlled_by = value
|
||||
if value == SELF:
|
||||
self.log.warning('switch to manual mode')
|
||||
for input_module in self.input_modules:
|
||||
if input_module.control_active:
|
||||
input_module.write_control_active(False)
|
||||
return Done
|
||||
|
||||
|
||||
class Loop(HasConvergence, MercuryChannel, Drivable):
|
||||
"""common base class for loops"""
|
||||
control_active = Parameter('control mode', BoolType())
|
||||
output_module = Attached(HasInput, mandatory=False)
|
||||
ctrlpars = Parameter(
|
||||
'pid (proportional band, integral time, differential time',
|
||||
StructOf(p=FloatRange(0, unit='$'), i=FloatRange(0, unit='min'), d=FloatRange(0, unit='min')),
|
||||
readonly=False,
|
||||
)
|
||||
enable_pid_table = Parameter('', BoolType(), readonly=False)
|
||||
|
||||
def initModule(self):
|
||||
super().initModule()
|
||||
if self.output_module:
|
||||
self.output_module.add_input(self)
|
||||
|
||||
def set_output(self, active):
|
||||
if active:
|
||||
if self.output_module and self.output_module.controlled_by != self.name:
|
||||
self.output_module.controlled_by = self.name
|
||||
else:
|
||||
if self.output_module and self.output_module.controlled_by != SELF:
|
||||
self.output_module.write_controlled_by(SELF)
|
||||
status = IDLE, 'control inactive'
|
||||
if self.status != status:
|
||||
self.status = status
|
||||
|
||||
def set_target(self, target):
|
||||
if self.control_active:
|
||||
self.set_output(True)
|
||||
else:
|
||||
self.log.warning('switch loop control on')
|
||||
self.write_control_active(True)
|
||||
self.target = target
|
||||
self.start_state()
|
||||
|
||||
def read_enable_pid_table(self):
|
||||
return self.query('0:LOOP:PIDT', off_on)
|
||||
|
||||
def write_enable_pid_table(self, value):
|
||||
return self.change('0:LOOP:PIDT', value, off_on)
|
||||
|
||||
def read_ctrlpars(self):
|
||||
# read all in one go, in order to reduce comm. traffic
|
||||
pid = self.multiquery('0:LOOP', ('P', 'I', 'D'))
|
||||
return {k: float(v) for k, v in zip('pid', pid)}
|
||||
|
||||
def write_ctrlpars(self, value):
|
||||
pid = self.multichange('0:LOOP', [(k, value[k.lower()]) for k in 'PID'])
|
||||
return {k.lower(): v for k, v in zip('PID', pid)}
|
||||
|
||||
|
||||
class HeaterOutput(HasInput, MercuryChannel, Writable):
|
||||
"""heater output
|
||||
|
||||
Remark:
|
||||
The hardware calculates the power from the voltage and the configured
|
||||
resistivity. As the measured heater current is available, the resistivity
|
||||
will be adjusted automatically, when true_power is True.
|
||||
"""
|
||||
channel_type = 'HTR'
|
||||
value = Parameter('heater output', FloatRange(unit='W'), readonly=False)
|
||||
target = Parameter('heater output', FloatRange(0, 100, unit='$'), readonly=False)
|
||||
resistivity = Parameter('heater resistivity', FloatRange(10, 1000, unit='Ohm'),
|
||||
readonly=False)
|
||||
true_power = Parameter('calculate power from measured current', BoolType(), readonly=False, default=True)
|
||||
limit = Parameter('heater output limit', FloatRange(0, 1000, unit='W'), readonly=False)
|
||||
volt = 0.0 # target voltage
|
||||
_last_target = None
|
||||
_volt_target = None
|
||||
|
||||
def read_limit(self):
|
||||
return self.query('HTR:VLIM') ** 2 / self.resistivity
|
||||
|
||||
def write_limit(self, value):
|
||||
result = self.change('HTR:VLIM', math.sqrt(value * self.resistivity))
|
||||
return result ** 2 / self.resistivity
|
||||
|
||||
def read_resistivity(self):
|
||||
if self.true_power:
|
||||
return self.resistivity
|
||||
return max(10, self.query('HTR:RES'))
|
||||
|
||||
def write_resistivity(self, value):
|
||||
self.resistivity = self.change('HTR:RES', max(10, value))
|
||||
if self._last_target is not None:
|
||||
if not self.true_power:
|
||||
self._volt_target = math.sqrt(self._last_target * self.resistivity)
|
||||
self.change('HTR:SIG:VOLT', self._volt_target)
|
||||
return Done
|
||||
|
||||
def read_status(self):
|
||||
status = IDLE, ('true power' if self.true_power else 'fixed resistivity')
|
||||
if self.status != status:
|
||||
return status
|
||||
return Done
|
||||
|
||||
def read_value(self):
|
||||
if self._last_target is None: # on init
|
||||
self.read_target()
|
||||
if not self.true_power:
|
||||
volt = self.query('HTR:SIG:VOLT')
|
||||
return volt ** 2 / max(10, self.resistivity)
|
||||
volt, current = self.multiquery('HTR:SIG', ('VOLT', 'CURR'))
|
||||
if volt > 0 and current > 0.0001 and self._last_target:
|
||||
res = volt / current
|
||||
tol = res * max(max(0.0003, abs(volt - self._volt_target)) / volt, 0.0001 / current, 0.0001)
|
||||
if abs(res - self.resistivity) > tol + 0.07 and self._last_target:
|
||||
self.write_resistivity(round(res, 1))
|
||||
if self.controlled_by == 0:
|
||||
self._volt_target = math.sqrt(self._last_target * self.resistivity)
|
||||
self.change('HTR:SIG:VOLT', self._volt_target)
|
||||
return volt * current
|
||||
|
||||
def read_target(self):
|
||||
if self.controlled_by != 0 and self.target:
|
||||
return 0
|
||||
if self._last_target is not None:
|
||||
return Done
|
||||
self._volt_target = self.query('HTR:SIG:VOLT')
|
||||
self.resistivity = max(10, self.query('HTR:RES'))
|
||||
self._last_target = self._volt_target ** 2 / max(10, self.resistivity)
|
||||
return self._last_target
|
||||
|
||||
def set_target(self, value):
|
||||
"""set the target without switching to manual
|
||||
|
||||
might be used by a software loop
|
||||
"""
|
||||
self._volt_target = math.sqrt(value * self.resistivity)
|
||||
self.change('HTR:SIG:VOLT', self._volt_target)
|
||||
self._last_target = value
|
||||
return value
|
||||
|
||||
def write_target(self, value):
|
||||
self.write_controlled_by(SELF)
|
||||
return self.set_target(value)
|
||||
|
||||
|
||||
class TemperatureLoop(TemperatureSensor, Loop, Drivable):
|
||||
channel_type = 'TEMP,HTR'
|
||||
output_module = Attached(HeaterOutput, mandatory=False)
|
||||
ramp = Parameter('ramp rate', FloatRange(0, unit='K/min'), readonly=False)
|
||||
enable_ramp = Parameter('enable ramp rate', BoolType(), readonly=False)
|
||||
setpoint = Parameter('working setpoint (differs from target when ramping)', FloatRange(0, unit='$'))
|
||||
auto_flow = Parameter('enable auto flow', BoolType(), readonly=False)
|
||||
_last_setpoint_change = None
|
||||
|
||||
def doPoll(self):
|
||||
super().doPoll()
|
||||
self.read_setpoint()
|
||||
|
||||
def read_control_active(self):
|
||||
active = self.query('TEMP:LOOP:ENAB', off_on)
|
||||
self.set_output(active)
|
||||
return active
|
||||
|
||||
def write_control_active(self, value):
|
||||
self.set_output(value)
|
||||
return self.change('TEMP:LOOP:ENAB', value, off_on)
|
||||
|
||||
@nopoll # polled by read_setpoint
|
||||
def read_target(self):
|
||||
if self.read_enable_ramp():
|
||||
return self.target
|
||||
self.setpoint = self.query('TEMP:LOOP:TSET')
|
||||
return self.setpoint
|
||||
|
||||
def read_setpoint(self):
|
||||
setpoint = self.query('TEMP:LOOP:TSET')
|
||||
if self.enable_ramp:
|
||||
if setpoint == self.setpoint:
|
||||
# update target when working setpoint does no longer change
|
||||
if setpoint != self.target and self._last_setpoint_change is not None:
|
||||
unchanged_since = time.time() - self._last_setpoint_change
|
||||
if unchanged_since > max(12.0, 0.06 / max(1e-4, self.ramp)):
|
||||
self.target = self.setpoint
|
||||
return setpoint
|
||||
self._last_setpoint_change = time.time()
|
||||
else:
|
||||
self.target = setpoint
|
||||
return setpoint
|
||||
|
||||
def write_target(self, value):
|
||||
target = self.change('TEMP:LOOP:TSET', value)
|
||||
if self.enable_ramp:
|
||||
self._last_setpoint_change = None
|
||||
self.set_target(value)
|
||||
else:
|
||||
self.set_target(target)
|
||||
return Done
|
||||
|
||||
def read_enable_ramp(self):
|
||||
return self.query('TEMP:LOOP:RENA', off_on)
|
||||
|
||||
def write_enable_ramp(self, value):
|
||||
return self.change('TEMP:LOOP:RENA', value, off_on)
|
||||
|
||||
def read_auto_flow(self):
|
||||
return self.query('TEMP:LOOP:FAUT', off_on)
|
||||
|
||||
def write_auto_flow(self, value):
|
||||
return self.change('TEMP:LOOP:FAUT', value, off_on)
|
||||
|
||||
def read_ramp(self):
|
||||
result = self.query('TEMP:LOOP:RSET')
|
||||
return min(9e99, result)
|
||||
|
||||
def write_ramp(self, value):
|
||||
# use 0 or a very big value for switching off ramp
|
||||
if not value:
|
||||
self.write_enable_ramp(0)
|
||||
return 0
|
||||
if value >= 9e99:
|
||||
self.change('TEMP:LOOP:RSET', 'inf', as_string)
|
||||
self.write_enable_ramp(0)
|
||||
return 9e99
|
||||
self.write_enable_ramp(1)
|
||||
return self.change('TEMP:LOOP:RSET', max(1e-4, value))
|
||||
|
||||
|
||||
class PressureSensor(MercuryChannel, Readable):
|
||||
channel_type = 'PRES'
|
||||
value = Parameter(unit='mbar')
|
||||
|
||||
def read_value(self):
|
||||
return self.query('PRES:SIG:PRES')
|
||||
|
||||
|
||||
class ValvePos(HasInput, MercuryChannel, Drivable):
|
||||
channel_type = 'PRES,AUX'
|
||||
value = Parameter('value pos', FloatRange(unit='%'), readonly=False)
|
||||
target = Parameter('valve pos target', FloatRange(0, 100, unit='$'), readonly=False)
|
||||
|
||||
def doPoll(self):
|
||||
self.read_status()
|
||||
|
||||
def read_value(self):
|
||||
return self.query('AUX:SIG:PERC')
|
||||
|
||||
def read_status(self):
|
||||
self.read_value()
|
||||
if abs(self.value - self.target) < 0.01:
|
||||
return 'IDLE', 'at target'
|
||||
return 'BUSY', 'moving'
|
||||
|
||||
def read_target(self):
|
||||
return self.query('PRES:LOOP:FSET')
|
||||
|
||||
def write_target(self, value):
|
||||
self.write_controlled_by(SELF)
|
||||
return self.change('PRES:LOOP:FSET', value)
|
||||
|
||||
|
||||
class PressureLoop(PressureSensor, Loop, Drivable):
|
||||
channel_type = 'PRES,AUX'
|
||||
output_module = Attached(ValvePos, mandatory=False)
|
||||
|
||||
def read_control_active(self):
|
||||
active = self.query('PRES:LOOP:FAUT', off_on)
|
||||
self.set_output(active)
|
||||
return active
|
||||
|
||||
def write_control_active(self, value):
|
||||
self.set_output(value)
|
||||
return self.change('PRES:LOOP:FAUT', value, off_on)
|
||||
|
||||
def read_target(self):
|
||||
return self.query('PRES:LOOP:PRST')
|
||||
|
||||
def write_target(self, value):
|
||||
target = self.change('PRES:LOOP:PRST', value)
|
||||
self.set_target(target)
|
||||
return Done
|
||||
|
||||
|
||||
class HeLevel(MercuryChannel, Readable):
|
||||
"""He level meter channel
|
||||
|
||||
The Mercury system does not support automatic switching between fast
|
||||
(when filling) and slow (when consuming). We have to handle this by software.
|
||||
"""
|
||||
channel_type = 'LVL'
|
||||
sample_rate = Parameter('_', EnumType(slow=0, fast=1), readonly=False)
|
||||
hysteresis = Parameter('hysteresis for detection of increase', FloatRange(0, 100, unit='%'),
|
||||
default=5, readonly=False)
|
||||
fast_timeout = Parameter('time to switch to slow after last increase', FloatRange(0, unit='sec'),
|
||||
default=300, readonly=False)
|
||||
_min_level = 999
|
||||
_max_level = -999
|
||||
_last_increase = None # None when in slow mode, last increase time in fast mode
|
||||
|
||||
def check_rate(self, sample_rate):
|
||||
"""check changes in rate
|
||||
|
||||
:param sample_rate: (int or enum) 0: slow, 1: fast
|
||||
initialize affected attributes
|
||||
"""
|
||||
if sample_rate != 0: # fast
|
||||
if not self._last_increase:
|
||||
self._last_increase = time.time()
|
||||
self._max_level = -999
|
||||
elif self._last_increase:
|
||||
self._last_increase = None
|
||||
self._min_level = 999
|
||||
return sample_rate
|
||||
|
||||
def read_sample_rate(self):
|
||||
return self.check_rate(self.query('LVL:HEL:PULS:SLOW', fast_slow))
|
||||
|
||||
def write_sample_rate(self, value):
|
||||
self.check_rate(value)
|
||||
return self.change('LVL:HEL:PULS:SLOW', value, fast_slow)
|
||||
|
||||
def read_value(self):
|
||||
level = self.query('LVL:SIG:HEL:LEV')
|
||||
# handle automatic switching depending on increase
|
||||
now = time.time()
|
||||
if self._last_increase: # fast mode
|
||||
if level > self._max_level:
|
||||
self._last_increase = now
|
||||
self._max_level = level
|
||||
elif now > self._last_increase + self.fast_timeout:
|
||||
# no increase since fast timeout -> slow
|
||||
self.write_sample_rate(self.sample_rate.slow)
|
||||
else:
|
||||
if level > self._min_level + self.hysteresis:
|
||||
# substantial increase -> fast
|
||||
self.write_sample_rate(self.sample_rate.fast)
|
||||
else:
|
||||
self._min_level = min(self._min_level, level)
|
||||
return level
|
||||
|
||||
|
||||
class N2Level(MercuryChannel, Readable):
|
||||
channel_type = 'LVL'
|
||||
|
||||
def read_value(self):
|
||||
return self.query('LVL:SIG:NIT:LEV')
|
||||
|
||||
|
||||
# TODO: magnet power supply
|
267
frappy_psi/motorvalve.py
Normal file
267
frappy_psi/motorvalve.py
Normal file
@ -0,0 +1,267 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
#
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
#
|
||||
# *****************************************************************************
|
||||
|
||||
"""motor valve using a trinamic PD-1161 motor
|
||||
|
||||
the valve has an end switch connected to the 'home' digital input
|
||||
of the motor controller. Motor settings for the currently used valve:
|
||||
|
||||
[valve_motor]
|
||||
description = valve motor
|
||||
class = frappy_psi.trinamic.Motor
|
||||
maxcurrent=0.3 # a value corresponding to the torque needed to firmly close the valve.
|
||||
move_limit=9999 # no move limit needed
|
||||
acceleration=150
|
||||
encoder_tolerance=3.6 # typical value
|
||||
auto_reset=True # motor stalls on closing
|
||||
|
||||
[valve]
|
||||
description = trinamic angular motor valve
|
||||
class = frappy_psi.motorvalve.MotorValve
|
||||
motor = valve_motor
|
||||
turns = 9 # number of turns needed to open fully
|
||||
speed = 400 # close to max. speed
|
||||
lowspeed = 50 # speed for final closing / reference run
|
||||
"""
|
||||
|
||||
from frappy.core import Drivable, Parameter, EnumType, Attached, FloatRange, \
|
||||
Command, IDLE, BUSY, WARN, ERROR, Done, PersistentParam, PersistentMixin
|
||||
from frappy.errors import HardwareError
|
||||
from frappy_psi.trinamic import Motor
|
||||
from frappy.lib.statemachine import StateMachine, Retry, Stop
|
||||
|
||||
|
||||
class MotorValve(PersistentMixin, Drivable):
|
||||
motor = Attached(Motor)
|
||||
value = Parameter('current state', EnumType(
|
||||
closed=0, opened=1, undefined=-1), default=-1)
|
||||
target = Parameter('target state', EnumType(close=0, open=1))
|
||||
turns = Parameter('number of turns to open', FloatRange(), readonly=False, group='settings')
|
||||
speed = Parameter('speed for far moves', FloatRange(), readonly=False, group='settings')
|
||||
lowspeed = Parameter('speed for finding closed position', FloatRange(), readonly=False, group='settings')
|
||||
closed_pos = PersistentParam('fully closed position', FloatRange(),
|
||||
persistent='auto', export=True, default=-999) # TODO: export=False
|
||||
pollinterval = Parameter(group='settings')
|
||||
|
||||
_state = None
|
||||
|
||||
# remark: the home button must be touched when the motor is at zero
|
||||
|
||||
def earlyInit(self):
|
||||
super().earlyInit()
|
||||
self._state = StateMachine(logger=self.log, count=3, cleanup=self.handle_error)
|
||||
|
||||
def write_target(self, target):
|
||||
if self.status[0] == ERROR:
|
||||
raise HardwareError('%s: need refrun' % self.status[1])
|
||||
self.target = target
|
||||
self._state.start(self.goto_target, count=3)
|
||||
return Done
|
||||
|
||||
def goto_target(self, state):
|
||||
self.value = 'undefined'
|
||||
if self.motor.isBusy():
|
||||
mot_target = 0 if self.target == self.target.close else self.turns * 360
|
||||
if abs(mot_target - self.motor.target) > self.motor.tolerance:
|
||||
self.motor.stop()
|
||||
return self.open_valve if self.target == self.target.open else self.close_valve
|
||||
|
||||
def read_value(self):
|
||||
"""determine value and status"""
|
||||
if self.status[0] == ERROR:
|
||||
return 'undefined'
|
||||
if self.motor.isBusy():
|
||||
return Done
|
||||
motpos = self.motor.read_value()
|
||||
if self.motor.read_home():
|
||||
if motpos > 360:
|
||||
self.status = ERROR, 'home button must be released at this position'
|
||||
elif motpos > 5:
|
||||
if self.status[0] != ERROR:
|
||||
self.status = WARN, 'position undefined'
|
||||
elif motpos < -360:
|
||||
self.status = ERROR, 'motor must not reach -1 turn!'
|
||||
elif abs(motpos - self.closed_pos) < self.motor.tolerance:
|
||||
self.status = IDLE, 'closed'
|
||||
return 'closed'
|
||||
self.status = WARN, 'nearly closed'
|
||||
return 'undefined'
|
||||
if abs(motpos - self.turns * 360) < 5:
|
||||
self.status = IDLE, 'opened'
|
||||
return 'opened'
|
||||
if motpos < 5:
|
||||
self.status = ERROR, 'home button must be engaged at this position'
|
||||
elif self.status[0] != ERROR:
|
||||
self.status = WARN, 'position undefined'
|
||||
return 'undefined'
|
||||
|
||||
def open_valve(self, state):
|
||||
if state.init:
|
||||
self.closed_pos = -999
|
||||
self.value = 'undefined'
|
||||
self.status = BUSY, 'opening'
|
||||
self.motor.write_speed(self.speed)
|
||||
self.motor.write_target(self.turns * 360)
|
||||
if self.motor.isBusy():
|
||||
if self.motor.home and self.motor.value > 360:
|
||||
self.motor.stop()
|
||||
self.status = ERROR, 'opening valve failed (home switch not released)'
|
||||
return None
|
||||
return Retry()
|
||||
motvalue = self.motor.read_value()
|
||||
if abs(motvalue - self.turns * 360) < 5:
|
||||
self.read_value() # value = opened, status = IDLE
|
||||
else:
|
||||
if state.count > 0:
|
||||
state.count -= 1
|
||||
self.log.info('target %g not reached, try again', motvalue)
|
||||
return self.goto_target
|
||||
self.status = ERROR, 'opening valve failed (motor target not reached)'
|
||||
return None
|
||||
|
||||
def close_valve(self, state):
|
||||
if state.init:
|
||||
self.closed_pos = -999
|
||||
self.status = BUSY, 'closing'
|
||||
self.motor.write_speed(self.speed)
|
||||
self.motor.write_target(0)
|
||||
if self.motor.isBusy():
|
||||
if self.motor.home:
|
||||
return self.find_closed
|
||||
return Retry()
|
||||
motvalue = self.motor.read_value()
|
||||
if abs(motvalue) > 5:
|
||||
if state.count > 0:
|
||||
state.count -= 1
|
||||
self.log.info('target %g not reached, try again', motvalue)
|
||||
return self.goto_target
|
||||
self.status = ERROR, 'closing valve failed (zero not reached)'
|
||||
return None
|
||||
if self.read_value() == self.value.undefined:
|
||||
if self.status[0] != ERROR:
|
||||
return self.find_closed
|
||||
return None
|
||||
|
||||
def find_closed(self, state):
|
||||
"""drive with low speed until motor stalls"""
|
||||
if state.init:
|
||||
self.motor.write_speed(self.lowspeed)
|
||||
state.prev = self.motor.value
|
||||
self.motor.write_target(-360)
|
||||
if self.motor.isBusy():
|
||||
if not self.motor.home:
|
||||
self.motor.stop()
|
||||
return None
|
||||
return Retry()
|
||||
motvalue = self.motor.read_value()
|
||||
if motvalue < -360:
|
||||
self.read_value() # status -> error
|
||||
return None
|
||||
if motvalue < state.prev - 5:
|
||||
# moved by more than 5 deg
|
||||
state.prev = self.motor.value
|
||||
self.motor.write_target(-360)
|
||||
return Retry()
|
||||
if motvalue > 5:
|
||||
self.status = ERROR, 'closing valve failed (zero not reached)'
|
||||
return None
|
||||
if motvalue < -355:
|
||||
self.status = ERROR, 'closing valve failed (does not stop)'
|
||||
return None
|
||||
self.closed_pos = motvalue
|
||||
self.read_value() # value = closed, status = IDLE
|
||||
return None
|
||||
|
||||
@Command
|
||||
def ref_run(self):
|
||||
"""start reference run"""
|
||||
self.target = 'close'
|
||||
self._state.start(self.ref_home, count=3)
|
||||
|
||||
@Command
|
||||
def stop(self):
|
||||
self._state.stop()
|
||||
self.motor.stop()
|
||||
|
||||
def ref_home(self, state):
|
||||
if state.init:
|
||||
self.closed_pos = -999
|
||||
self.motor.write_speed(self.lowspeed)
|
||||
if self.motor.read_home():
|
||||
self.status = BUSY, 'refrun: release home'
|
||||
self.motor.write_target(self.motor.read_value() + 360)
|
||||
return self.ref_released
|
||||
self.status = BUSY, 'refrun: find home'
|
||||
self.motor.write_target(self.motor.read_value() - (self.turns + 1) * 360)
|
||||
if not self.motor.isBusy():
|
||||
self.status = ERROR, 'ref run failed, can not find home switch'
|
||||
return None
|
||||
if not self.motor.home:
|
||||
return Retry()
|
||||
self.motor.write_speed(self.lowspeed)
|
||||
state.prev = self.motor.read_value()
|
||||
self.motor.write_target(state.prev - 360)
|
||||
self.status = BUSY, 'refrun: find closed'
|
||||
return self.ref_closed
|
||||
|
||||
def ref_released(self, state):
|
||||
if self.motor.isBusy():
|
||||
if self.motor.home:
|
||||
return Retry()
|
||||
elif self.motor.read_home():
|
||||
if state.count > 0:
|
||||
state.count -= 1
|
||||
self.log.info('home switch not released, try again')
|
||||
self.motor.write_target(self.motor.target)
|
||||
return Retry()
|
||||
self.status = ERROR, 'ref run failed, can not release home switch'
|
||||
return None
|
||||
return self.ref_home
|
||||
|
||||
def ref_closed(self, state):
|
||||
if self.motor.isBusy():
|
||||
if not self.motor.home:
|
||||
self.motor.stop()
|
||||
return None
|
||||
return Retry()
|
||||
self.motor.set_zero(max(-50, (self.motor.read_value() - state.prev) * 0.5))
|
||||
self.read_value() # check home button is valid
|
||||
if abs(self.motor.target - self.motor.value) < 5:
|
||||
self.status = ERROR, 'ref run failed, does not stop'
|
||||
if self.status[0] == ERROR:
|
||||
return None
|
||||
self.log.info('refrun successful')
|
||||
return self.close_valve
|
||||
|
||||
def handle_error(self, state):
|
||||
if state.stopped: # stop or restart case
|
||||
if state.stopped is Stop:
|
||||
self.status = WARN, 'stopped'
|
||||
return None
|
||||
if state.count > 0:
|
||||
state.count -= 1
|
||||
self.log.info('error %r, try again', state.last_error)
|
||||
state.default_cleanup(state) # log error cause
|
||||
state.last_error = None
|
||||
return self.goto_target # try again
|
||||
self.status = ERROR, str(state.last_error)
|
||||
return state.default_cleanup(state)
|
744
frappy_psi/ppms.py
Normal file
744
frappy_psi/ppms.py
Normal file
@ -0,0 +1,744 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""PPMS driver
|
||||
|
||||
The PPMS hardware has some special requirements:
|
||||
|
||||
- the communication to the hardware happens through windows COM
|
||||
- all measured data including state are handled by one request/reply pair GETDAT?<mask>
|
||||
- for each channel, the settings are handled through a single request/reply pair,
|
||||
needing a mechanism to treat a single parameter change correctly.
|
||||
|
||||
Polling of value and status is done commonly for all modules. For each registered module
|
||||
<module>.update_value_status() is called in order to update their value and status.
|
||||
"""
|
||||
|
||||
import threading
|
||||
import time
|
||||
from ast import literal_eval # convert string as comma separated numbers into tuple
|
||||
|
||||
from frappy.datatypes import BoolType, EnumType, \
|
||||
FloatRange, IntRange, StatusType, StringType
|
||||
from frappy.errors import HardwareError
|
||||
from frappy.lib import clamp
|
||||
from frappy.lib.enum import Enum
|
||||
from frappy.modules import Communicator, Done, \
|
||||
Drivable, Parameter, Property, Readable
|
||||
from frappy.io import HasIO
|
||||
from frappy.rwhandler import CommonReadHandler, CommonWriteHandler
|
||||
|
||||
try:
|
||||
import frappy_psi.ppmswindows as ppmshw
|
||||
except ImportError:
|
||||
print('use simulation instead')
|
||||
import frappy_psi.ppmssim as ppmshw
|
||||
|
||||
|
||||
class Main(Communicator):
|
||||
"""ppms communicator module"""
|
||||
|
||||
pollinterval = Parameter('poll interval', FloatRange(), readonly=False, default=2)
|
||||
data = Parameter('internal', StringType(), export=True, # export for test only
|
||||
default="", readonly=True)
|
||||
|
||||
class_id = Property('Quantum Design class id', StringType(), export=False)
|
||||
|
||||
_channel_names = [
|
||||
'packed_status', 'temp', 'field', 'position', 'r1', 'i1', 'r2', 'i2',
|
||||
'r3', 'i3', 'r4', 'i4', 'v1', 'v2', 'digital', 'cur1', 'pow1', 'cur2', 'pow2',
|
||||
'p', 'u20', 'u21', 'u22', 'ts', 'u24', 'u25', 'u26', 'u27', 'u28', 'u29']
|
||||
assert len(_channel_names) == 30
|
||||
_channel_to_index = dict(((channel, i) for i, channel in enumerate(_channel_names)))
|
||||
_status_bitpos = {'temp': 0, 'field': 4, 'chamber': 8, 'position': 12}
|
||||
|
||||
def earlyInit(self):
|
||||
super().earlyInit()
|
||||
self.modules = {}
|
||||
self._ppms_device = ppmshw.QDevice(self.class_id)
|
||||
self.lock = threading.Lock()
|
||||
|
||||
def register(self, other):
|
||||
self.modules[other.channel] = other
|
||||
|
||||
def communicate(self, command):
|
||||
"""GPIB command"""
|
||||
with self.lock:
|
||||
self.comLog('> %s' % command)
|
||||
reply = self._ppms_device.send(command)
|
||||
self.comLog("< %s", reply)
|
||||
return reply
|
||||
|
||||
def doPoll(self):
|
||||
self.read_data()
|
||||
|
||||
def read_data(self):
|
||||
mask = 1 # always get packed_status
|
||||
for channelname, channel in self.modules.items():
|
||||
if channel.enabled:
|
||||
mask |= 1 << self._channel_to_index.get(channelname, 0)
|
||||
# send, read and convert to floats and ints
|
||||
data = self.communicate('GETDAT? %d' % mask)
|
||||
reply = data.split(',')
|
||||
mask = int(reply.pop(0))
|
||||
reply.pop(0) # pop timestamp
|
||||
result = {}
|
||||
for bitpos, channelname in enumerate(self._channel_names):
|
||||
if mask & (1 << bitpos):
|
||||
result[channelname] = float(reply.pop(0))
|
||||
if 'temp' in result:
|
||||
result['tv'] = result['temp']
|
||||
if 'ts' in result:
|
||||
result['temp'] = result['ts']
|
||||
packed_status = int(result['packed_status'])
|
||||
result['chamber'] = None # 'chamber' must be in result for status, but value is ignored
|
||||
for channelname, channel in self.modules.items():
|
||||
channel.update_value_status(result.get(channelname, None), packed_status)
|
||||
return data # return data as string
|
||||
|
||||
|
||||
class PpmsBase(HasIO, Readable):
|
||||
"""common base for all ppms modules"""
|
||||
value = Parameter(needscfg=False)
|
||||
status = Parameter(needscfg=False)
|
||||
|
||||
enabled = True # default, if no parameter enable is defined
|
||||
_last_settings = None # used by several modules
|
||||
slow_pollfactor = 1
|
||||
|
||||
# as this pollinterval affects only the polling of settings
|
||||
# it would be confusing to export it.
|
||||
pollinterval = Parameter(export=False)
|
||||
|
||||
def initModule(self):
|
||||
super().initModule()
|
||||
self.io.register(self)
|
||||
|
||||
def doPoll(self):
|
||||
# polling is done by the main module
|
||||
# and PPMS does not deliver really more fresh values when polled more often
|
||||
pass
|
||||
|
||||
def update_value_status(self, value, packed_status):
|
||||
# update value and status
|
||||
# to be reimplemented for modules looking at packed_status
|
||||
if not self.enabled:
|
||||
self.status = (self.Status.DISABLED, 'disabled')
|
||||
return
|
||||
if value is None:
|
||||
self.status = (self.Status.ERROR, 'invalid value')
|
||||
else:
|
||||
self.value = value
|
||||
self.status = (self.Status.IDLE, '')
|
||||
|
||||
def comm_write(self, command):
|
||||
"""write command and check if result is OK"""
|
||||
reply = self.communicate(command)
|
||||
if reply != 'OK':
|
||||
raise HardwareError('bad reply %r to command %r' % (reply, command))
|
||||
|
||||
|
||||
class Channel(PpmsBase):
|
||||
"""channel base class"""
|
||||
|
||||
value = Parameter('main value of channels')
|
||||
enabled = Parameter('is this channel used?', readonly=False,
|
||||
datatype=BoolType(), default=False)
|
||||
|
||||
channel = Property('channel name',
|
||||
datatype=StringType(), export=False, default='')
|
||||
no = Property('channel number',
|
||||
datatype=IntRange(1, 4), export=False)
|
||||
|
||||
def earlyInit(self):
|
||||
super().earlyInit()
|
||||
if not self.channel:
|
||||
self.channel = self.name
|
||||
|
||||
|
||||
class UserChannel(Channel):
|
||||
"""user channel"""
|
||||
|
||||
no = Property('channel number',
|
||||
datatype=IntRange(0, 0), export=False, default=0)
|
||||
linkenable = Property('name of linked channel for enabling',
|
||||
datatype=StringType(), export=False, default='')
|
||||
|
||||
def write_enabled(self, enabled):
|
||||
other = self.io.modules.get(self.linkenable, None)
|
||||
if other:
|
||||
other.enabled = enabled
|
||||
return enabled
|
||||
|
||||
|
||||
class DriverChannel(Channel):
|
||||
"""driver channel"""
|
||||
|
||||
current = Parameter('driver current', readonly=False,
|
||||
datatype=FloatRange(0., 5000., unit='uA'))
|
||||
powerlimit = Parameter('power limit', readonly=False,
|
||||
datatype=FloatRange(0., 1000., unit='uW'))
|
||||
|
||||
param_names = 'current', 'powerlimit'
|
||||
|
||||
@CommonReadHandler(param_names)
|
||||
def read_params(self):
|
||||
no, self.current, self.powerlimit = literal_eval(
|
||||
self.communicate('DRVOUT? %d' % self.no))
|
||||
if self.no != no:
|
||||
raise HardwareError('DRVOUT command: channel number in reply does not match')
|
||||
|
||||
@CommonWriteHandler(param_names)
|
||||
def write_params(self, values):
|
||||
"""write parameters
|
||||
|
||||
:param values: a dict like object containing the parameters to be written
|
||||
"""
|
||||
self.read_params() # make sure parameters are up to date
|
||||
self.comm_write('DRVOUT %(no)d,%(current)g,%(powerlimit)g' % values)
|
||||
self.read_params() # read back
|
||||
|
||||
|
||||
class BridgeChannel(Channel):
|
||||
"""bridge channel"""
|
||||
|
||||
excitation = Parameter('excitation current', readonly=False,
|
||||
datatype=FloatRange(0.01, 5000., unit='uA'))
|
||||
powerlimit = Parameter('power limit', readonly=False,
|
||||
datatype=FloatRange(0.001, 1000., unit='uW'))
|
||||
dcflag = Parameter('True when excitation is DC (else AC)', readonly=False,
|
||||
datatype=BoolType())
|
||||
readingmode = Parameter('reading mode', readonly=False,
|
||||
datatype=EnumType(standard=0, fast=1, highres=2))
|
||||
voltagelimit = Parameter('voltage limit', readonly=False,
|
||||
datatype=FloatRange(0.0001, 100., unit='mV'))
|
||||
|
||||
param_names = 'enabled', 'enabled', 'powerlimit', 'dcflag', 'readingmode', 'voltagelimit'
|
||||
|
||||
@CommonReadHandler(param_names)
|
||||
def read_params(self):
|
||||
no, excitation, powerlimit, self.dcflag, self.readingmode, voltagelimit = literal_eval(
|
||||
self.communicate('BRIDGE? %d' % self.no))
|
||||
if self.no != no:
|
||||
raise HardwareError('DRVOUT command: channel number in reply does not match')
|
||||
self.enabled = excitation != 0 and powerlimit != 0 and voltagelimit != 0
|
||||
if excitation:
|
||||
self.excitation = excitation
|
||||
if powerlimit:
|
||||
self.powerlimit = powerlimit
|
||||
if voltagelimit:
|
||||
self.voltagelimit = voltagelimit
|
||||
|
||||
@CommonWriteHandler(param_names)
|
||||
def write_params(self, values):
|
||||
"""write parameters
|
||||
|
||||
:param values: a dict like object containing the parameters to be written
|
||||
"""
|
||||
self.read_params() # make sure parameters are up to date
|
||||
if not values['enabled']:
|
||||
values['excitation'] = 0
|
||||
values['powerlimit'] = 0
|
||||
values['voltagelimit'] = 0
|
||||
self.comm_write('BRIDGE %(no)d,%(enabled)g,%(powerlimit)g,%(dcflag)d,'
|
||||
'%(readingmode)d,%(voltagelimit)g' % values)
|
||||
self.read_params() # read back
|
||||
|
||||
|
||||
class Level(PpmsBase):
|
||||
"""helium level"""
|
||||
|
||||
value = Parameter(datatype=FloatRange(unit='%'))
|
||||
|
||||
channel = 'level'
|
||||
|
||||
def doPoll(self):
|
||||
self.read_value()
|
||||
|
||||
def update_value_status(self, value, packed_status):
|
||||
pass
|
||||
# must be a no-op
|
||||
# when called from Main.read_data, value is always None
|
||||
# value and status is polled via settings
|
||||
|
||||
def read_value(self):
|
||||
# ignore 'old reading' state of the flag, as this happens only for a short time
|
||||
return literal_eval(self.communicate('LEVEL?'))[0]
|
||||
|
||||
|
||||
class Chamber(PpmsBase, Drivable):
|
||||
"""sample chamber handling
|
||||
|
||||
value is an Enum, which is redundant with the status text
|
||||
"""
|
||||
|
||||
Status = Drivable.Status
|
||||
code_table = [
|
||||
# valuecode, status, statusname, opcode, targetname
|
||||
(0, Status.IDLE, 'unknown', 10, 'noop'),
|
||||
(1, Status.IDLE, 'purged_and_sealed', 1, 'purge_and_seal'),
|
||||
(2, Status.IDLE, 'vented_and_sealed', 2, 'vent_and_seal'),
|
||||
(3, Status.WARN, 'sealed_unknown', 0, 'seal_immediately'),
|
||||
(4, Status.BUSY, 'purge_and_seal', None, None),
|
||||
(5, Status.BUSY, 'vent_and_seal', None, None),
|
||||
(6, Status.BUSY, 'pumping_down', None, None),
|
||||
(8, Status.IDLE, 'pumping_continuously', 3, 'pump_continuously'),
|
||||
(9, Status.IDLE, 'venting_continuously', 4, 'vent_continuously'),
|
||||
(15, Status.ERROR, 'general_failure', None, None),
|
||||
]
|
||||
value_codes = {k: v for v, _, k, _, _ in code_table}
|
||||
target_codes = {k: v for v, _, _, _, k in code_table if k}
|
||||
name2opcode = {k: v for _, _, _, v, k in code_table if k}
|
||||
opcode2name = {v: k for _, _, _, v, k in code_table if k}
|
||||
status_map = {v: (c, k.replace('_', ' ')) for v, c, k, _, _ in code_table}
|
||||
value = Parameter(description='chamber state', datatype=EnumType(**value_codes), default=0)
|
||||
target = Parameter(description='chamber command', datatype=EnumType(**target_codes), default='noop')
|
||||
|
||||
channel = 'chamber'
|
||||
|
||||
def update_value_status(self, value, packed_status):
|
||||
status_code = (packed_status >> 8) & 0xf
|
||||
if status_code in self.status_map:
|
||||
self.value = status_code
|
||||
self.status = self.status_map[status_code]
|
||||
else:
|
||||
self.value = self.value_map['unknown']
|
||||
self.status = (self.Status.ERROR, 'unknown status code %d' % status_code)
|
||||
|
||||
def read_target(self):
|
||||
opcode = int(self.communicate('CHAMBER?'))
|
||||
return self.opcode2name[opcode]
|
||||
|
||||
def write_target(self, value):
|
||||
if value == self.target.noop:
|
||||
return self.target.noop
|
||||
opcode = self.name2opcode[self.target.enum(value).name]
|
||||
assert self.communicate('CHAMBER %d' % opcode) == 'OK'
|
||||
return self.read_target()
|
||||
|
||||
|
||||
class Temp(PpmsBase, Drivable):
|
||||
"""temperature"""
|
||||
|
||||
Status = Enum(
|
||||
Drivable.Status,
|
||||
RAMPING=370,
|
||||
STABILIZING=380,
|
||||
)
|
||||
value = Parameter(datatype=FloatRange(unit='K'))
|
||||
status = Parameter(datatype=StatusType(Status))
|
||||
target = Parameter(datatype=FloatRange(1.7, 402.0, unit='K'), needscfg=False)
|
||||
setpoint = Parameter('intermediate set point',
|
||||
datatype=FloatRange(1.7, 402.0, unit='K'))
|
||||
ramp = Parameter('ramping speed', readonly=False, default=0,
|
||||
datatype=FloatRange(0, 20, unit='K/min'))
|
||||
workingramp = Parameter('intermediate ramp value',
|
||||
datatype=FloatRange(0, 20, unit='K/min'), default=0)
|
||||
approachmode = Parameter('how to approach target!', readonly=False,
|
||||
datatype=EnumType(fast_settle=0, no_overshoot=1), default=0)
|
||||
timeout = Parameter('drive timeout, in addition to ramp time', readonly=False,
|
||||
datatype=FloatRange(0, unit='sec'), default=3600)
|
||||
general_stop = Property('respect general stop', datatype=BoolType(),
|
||||
default=True, value=False)
|
||||
STATUS_MAP = {
|
||||
1: (Status.IDLE, 'stable at target'),
|
||||
2: (Status.RAMPING, 'ramping'),
|
||||
5: (Status.STABILIZING, 'within tolerance'),
|
||||
6: (Status.STABILIZING, 'outside tolerance'),
|
||||
7: (Status.STABILIZING, 'filling/emptying reservoir'),
|
||||
10: (Status.WARN, 'standby'),
|
||||
13: (Status.WARN, 'control disabled'),
|
||||
14: (Status.ERROR, 'can not complete'),
|
||||
15: (Status.ERROR, 'general failure'),
|
||||
}
|
||||
|
||||
channel = 'temp'
|
||||
_stopped = False
|
||||
_expected_target_time = 0
|
||||
_last_change = 0 # 0 means no target change is pending
|
||||
_last_target = None # last reached target
|
||||
_cool_deadline = 0
|
||||
_wait_at10 = False
|
||||
_ramp_at_limit = False
|
||||
|
||||
param_names = 'setpoint', 'workingramp', 'approachmode'
|
||||
|
||||
@CommonReadHandler(param_names)
|
||||
def read_params(self):
|
||||
settings = literal_eval(self.communicate('TEMP?'))
|
||||
if settings == self._last_settings:
|
||||
# update parameters only on change, as 'ramp' and 'approachmode' are
|
||||
# not always sent to the hardware
|
||||
return
|
||||
self.setpoint, self.workingramp, self.approachmode = self._last_settings = settings
|
||||
if self.setpoint != 10 or not self._wait_at10:
|
||||
self.log.debug('read back target %g %r' % (self.setpoint, self._wait_at10))
|
||||
self.target = self.setpoint
|
||||
if self.workingramp != 2 or not self._ramp_at_limit:
|
||||
self.log.debug('read back ramp %g %r' % (self.workingramp, self._ramp_at_limit))
|
||||
self.ramp = self.workingramp
|
||||
|
||||
def _write_params(self, setpoint, ramp, approachmode):
|
||||
wait_at10 = False
|
||||
ramp_at_limit = False
|
||||
if self.value > 11:
|
||||
if setpoint <= 10:
|
||||
wait_at10 = True
|
||||
setpoint = 10
|
||||
elif self.value > setpoint:
|
||||
if ramp >= 2:
|
||||
ramp = 2
|
||||
ramp_at_limit = True
|
||||
self._wait_at10 = wait_at10
|
||||
self._ramp_at_limit = ramp_at_limit
|
||||
self.calc_expected(setpoint, ramp)
|
||||
self.log.debug(
|
||||
'change_temp v %r s %r r %r w %r l %r' % (self.value, setpoint, ramp, wait_at10, ramp_at_limit))
|
||||
self.comm_write('TEMP %g,%g,%d' % (setpoint, ramp, approachmode))
|
||||
self.read_params()
|
||||
|
||||
def update_value_status(self, value, packed_status):
|
||||
if value is None:
|
||||
self.status = (self.Status.ERROR, 'invalid value')
|
||||
return
|
||||
self.value = value
|
||||
status_code = packed_status & 0xf
|
||||
status = self.STATUS_MAP.get(status_code, (self.Status.ERROR, 'unknown status code %d' % status_code))
|
||||
now = time.time()
|
||||
if value > 11:
|
||||
# when starting from T > 50, this will be 15 min.
|
||||
# when starting from lower T, it will be less
|
||||
# when ramping with 2 K/min or less, the deadline is now
|
||||
self._cool_deadline = max(self._cool_deadline, now + min(40, value - 10) * 30) # 30 sec / K
|
||||
elif self._wait_at10:
|
||||
if now > self._cool_deadline:
|
||||
self._wait_at10 = False
|
||||
self._last_change = now
|
||||
self._write_params(self.target, self.ramp, self.approachmode)
|
||||
status = (self.Status.STABILIZING, 'waiting at 10 K')
|
||||
if self._last_change: # there was a change, which is not yet confirmed by hw
|
||||
if now > self._last_change + 5:
|
||||
self._last_change = 0 # give up waiting for busy
|
||||
elif self.isDriving(status) and status != self._status_before_change:
|
||||
self.log.debug('time needed to change to busy: %.3g', now - self._last_change)
|
||||
self._last_change = 0
|
||||
else:
|
||||
status = (self.Status.BUSY, 'changed target')
|
||||
if abs(self.value - self.target) < self.target * 0.01:
|
||||
self._last_target = self.target
|
||||
elif self._last_target is None:
|
||||
self._last_target = self.value
|
||||
if self._stopped:
|
||||
# combine 'stopped' with current status text
|
||||
if status[0] == self.Status.IDLE:
|
||||
status = (status[0], 'stopped')
|
||||
else:
|
||||
status = (status[0], 'stopping (%s)' % status[1])
|
||||
if self._expected_target_time:
|
||||
# handle timeout
|
||||
if self.isDriving(status):
|
||||
if now > self._expected_target_time + self.timeout:
|
||||
status = (self.Status.WARN, 'timeout while %s' % status[1])
|
||||
else:
|
||||
self._expected_target_time = 0
|
||||
self.status = status
|
||||
|
||||
def write_target(self, target):
|
||||
self._stopped = False
|
||||
if abs(self.target - self.value) <= 2e-5 * target and target == self.target:
|
||||
return None
|
||||
self._status_before_change = self.status
|
||||
self.status = (self.Status.BUSY, 'changed target')
|
||||
self._last_change = time.time()
|
||||
self._write_params(target, self.ramp, self.approachmode)
|
||||
self.log.debug('write_target %s' % repr((self.setpoint, target, self._wait_at10)))
|
||||
return target
|
||||
|
||||
def write_approachmode(self, value):
|
||||
if self.isDriving():
|
||||
self._write_params(self.setpoint, self.ramp, value)
|
||||
return Done
|
||||
self.approachmode = value
|
||||
return Done # do not execute TEMP command, as this would trigger an unnecessary T change
|
||||
|
||||
def write_ramp(self, value):
|
||||
if self.isDriving():
|
||||
self._write_params(self.setpoint, value, self.approachmode)
|
||||
return Done
|
||||
self.ramp = value
|
||||
return Done # do not execute TEMP command, as this would trigger an unnecessary T change
|
||||
|
||||
def calc_expected(self, target, ramp):
|
||||
self._expected_target_time = time.time() + abs(target - self.value) * 60.0 / max(0.1, ramp)
|
||||
|
||||
def stop(self):
|
||||
if not self.isDriving():
|
||||
return
|
||||
if self.status[0] != self.Status.STABILIZING:
|
||||
# we are not near target
|
||||
newtarget = clamp(self._last_target, self.value, self.target)
|
||||
if newtarget != self.target:
|
||||
self.log.debug('stop at %s K', newtarget)
|
||||
self.write_target(newtarget)
|
||||
self.status = self.status[0], 'stopping (%s)' % self.status[1]
|
||||
self._stopped = True
|
||||
|
||||
|
||||
class Field(PpmsBase, Drivable):
|
||||
"""magnetic field"""
|
||||
|
||||
Status = Enum(
|
||||
Drivable.Status,
|
||||
PREPARED=150,
|
||||
PREPARING=340,
|
||||
RAMPING=370,
|
||||
STABILIZING=380,
|
||||
FINALIZING=390,
|
||||
)
|
||||
value = Parameter(datatype=FloatRange(unit='T'))
|
||||
status = Parameter(datatype=StatusType(Status))
|
||||
target = Parameter(datatype=FloatRange(-15, 15, unit='T')) # poll only one parameter
|
||||
ramp = Parameter('ramping speed', readonly=False,
|
||||
datatype=FloatRange(0.064, 1.19, unit='T/min'), default=0.19)
|
||||
approachmode = Parameter('how to approach target', readonly=False,
|
||||
datatype=EnumType(linear=0, no_overshoot=1, oscillate=2), default=0)
|
||||
persistentmode = Parameter('what to do after changing field', readonly=False,
|
||||
datatype=EnumType(persistent=0, driven=1), default=0)
|
||||
|
||||
STATUS_MAP = {
|
||||
1: (Status.IDLE, 'persistent mode'),
|
||||
2: (Status.PREPARING, 'switch warming'),
|
||||
3: (Status.FINALIZING, 'switch cooling'),
|
||||
4: (Status.IDLE, 'driven stable'),
|
||||
5: (Status.STABILIZING, 'driven final'),
|
||||
6: (Status.RAMPING, 'charging'),
|
||||
7: (Status.RAMPING, 'discharging'),
|
||||
8: (Status.ERROR, 'current error'),
|
||||
11: (Status.ERROR, 'probably quenched'),
|
||||
15: (Status.ERROR, 'general failure'),
|
||||
}
|
||||
|
||||
channel = 'field'
|
||||
_stopped = False
|
||||
_last_target = None # last reached target
|
||||
_last_change = 0 # means no target change is pending
|
||||
|
||||
param_names = 'target', 'ramp', 'approachmode', 'persistentmode'
|
||||
|
||||
@CommonReadHandler(param_names)
|
||||
def read_params(self):
|
||||
settings = literal_eval(self.communicate('FIELD?'))
|
||||
# print('last_settings tt %s' % repr(self._last_settings))
|
||||
if settings == self._last_settings:
|
||||
# we update parameters only on change, as 'ramp' and 'approachmode' are
|
||||
# not always sent to the hardware
|
||||
return
|
||||
target, ramp, self.approachmode, self.persistentmode = self._last_settings = settings
|
||||
self.target = round(target * 1e-4, 7)
|
||||
self.ramp = ramp * 6e-3
|
||||
|
||||
def _write_params(self, target, ramp, approachmode, persistentmode):
|
||||
self.comm_write('FIELD %g,%g,%d,%d' % (
|
||||
target * 1e+4, ramp / 6e-3, approachmode, persistentmode))
|
||||
self.read_params()
|
||||
|
||||
def update_value_status(self, value, packed_status):
|
||||
if value is None:
|
||||
self.status = (self.Status.ERROR, 'invalid value')
|
||||
return
|
||||
self.value = round(value * 1e-4, 7)
|
||||
status_code = (packed_status >> 4) & 0xf
|
||||
status = self.STATUS_MAP.get(status_code, (self.Status.ERROR, 'unknown status code %d' % status_code))
|
||||
now = time.time()
|
||||
if self._last_change: # there was a change, which is not yet confirmed by hw
|
||||
if status_code == 1: # persistent mode
|
||||
# leads are ramping (ppms has no extra status code for this!)
|
||||
if now < self._last_change + 30:
|
||||
status = (self.Status.PREPARING, 'ramping leads')
|
||||
else:
|
||||
status = (self.Status.WARN, 'timeout when ramping leads')
|
||||
elif now > self._last_change + 5:
|
||||
self._last_change = 0 # give up waiting for driving
|
||||
elif self.isDriving(status) and status != self._status_before_change:
|
||||
self._last_change = 0
|
||||
self.log.debug('time needed to change to busy: %.3g', now - self._last_change)
|
||||
else:
|
||||
status = (self.Status.BUSY, 'changed target')
|
||||
if abs(self.target - self.value) <= 1e-4:
|
||||
self._last_target = self.target
|
||||
elif self._last_target is None:
|
||||
self._last_target = self.value
|
||||
if self._stopped:
|
||||
# combine 'stopped' with current status text
|
||||
if status[0] == self.Status.IDLE:
|
||||
status = (status[0], 'stopped')
|
||||
else:
|
||||
status = (status[0], 'stopping (%s)' % status[1])
|
||||
self.status = status
|
||||
|
||||
def write_target(self, target):
|
||||
if abs(self.target - self.value) <= 2e-5 and target == self.target:
|
||||
self.target = target
|
||||
return None # avoid ramping leads
|
||||
self._status_before_change = self.status
|
||||
self._stopped = False
|
||||
self._last_change = time.time()
|
||||
self.status = (self.Status.BUSY, 'changed target')
|
||||
self._write_params(target, self.ramp, self.approachmode, self.persistentmode)
|
||||
return Done
|
||||
|
||||
def write_persistentmode(self, mode):
|
||||
if abs(self.target - self.value) <= 2e-5 and mode == self.persistentmode:
|
||||
self.persistentmode = mode
|
||||
return None # avoid ramping leads
|
||||
self._last_change = time.time()
|
||||
self._status_before_change = self.status
|
||||
self._stopped = False
|
||||
self.status = (self.Status.BUSY, 'changed persistent mode')
|
||||
self._write_params(self.target, self.ramp, self.approachmode, mode)
|
||||
return Done
|
||||
|
||||
def write_ramp(self, value):
|
||||
self.ramp = value
|
||||
if self.isDriving():
|
||||
self._write_params(self.target, value, self.approachmode, self.persistentmode)
|
||||
return Done
|
||||
return None # do not execute FIELD command, as this would trigger a ramp up of leads current
|
||||
|
||||
def write_approachmode(self, value):
|
||||
if self.isDriving():
|
||||
self._write_params(self.target, self.ramp, value, self.persistentmode)
|
||||
return Done
|
||||
return None # do not execute FIELD command, as this would trigger a ramp up of leads current
|
||||
|
||||
def stop(self):
|
||||
if not self.isDriving():
|
||||
return
|
||||
newtarget = clamp(self._last_target, self.value, self.target)
|
||||
if newtarget != self.target:
|
||||
self.log.debug('stop at %s T', newtarget)
|
||||
self.write_target(newtarget)
|
||||
self.status = (self.status[0], 'stopping (%s)' % self.status[1])
|
||||
self._stopped = True
|
||||
|
||||
|
||||
class Position(PpmsBase, Drivable):
|
||||
"""rotator position"""
|
||||
|
||||
Status = Drivable.Status
|
||||
|
||||
value = Parameter(datatype=FloatRange(unit='deg'))
|
||||
target = Parameter(datatype=FloatRange(-720., 720., unit='deg'))
|
||||
enabled = Parameter('is this channel used?', readonly=False,
|
||||
datatype=BoolType(), default=True)
|
||||
speed = Parameter('motor speed', readonly=False, default=12,
|
||||
datatype=FloatRange(0.8, 12, unit='deg/sec'))
|
||||
STATUS_MAP = {
|
||||
1: (Status.IDLE, 'at target'),
|
||||
5: (Status.BUSY, 'moving'),
|
||||
8: (Status.IDLE, 'at limit'),
|
||||
9: (Status.IDLE, 'at index'),
|
||||
15: (Status.ERROR, 'general failure'),
|
||||
}
|
||||
|
||||
channel = 'position'
|
||||
_stopped = False
|
||||
_last_target = None # last reached target
|
||||
_last_change = 0
|
||||
_within_target = 0 # time since we are within target
|
||||
|
||||
param_names = 'target', 'speed'
|
||||
|
||||
@CommonReadHandler(param_names)
|
||||
def read_params(self):
|
||||
settings = literal_eval(self.communicate('MOVE?'))
|
||||
if settings == self._last_settings:
|
||||
# we update parameters only on change, as 'speed' is
|
||||
# not always sent to the hardware
|
||||
return
|
||||
self.target, _, speed = self._last_settings = settings
|
||||
self.speed = (15 - speed) * 0.8
|
||||
|
||||
def _write_params(self, target, speed):
|
||||
speed = int(round(min(14, max(0, 15 - speed / 0.8)), 0))
|
||||
self.comm_write('MOVE %g,%d,%d' % (target, 0, speed))
|
||||
return self.read_params()
|
||||
|
||||
def update_value_status(self, value, packed_status):
|
||||
if not self.enabled:
|
||||
self.status = (self.Status.DISABLED, 'disabled')
|
||||
return
|
||||
if value is None:
|
||||
self.status = (self.Status.ERROR, 'invalid value')
|
||||
return
|
||||
self.value = value
|
||||
status_code = (packed_status >> 12) & 0xf
|
||||
status = self.STATUS_MAP.get(status_code, (self.Status.ERROR, 'unknown status code %d' % status_code))
|
||||
if self._last_change: # there was a change, which is not yet confirmed by hw
|
||||
now = time.time()
|
||||
if now > self._last_change + 5:
|
||||
self._last_change = 0 # give up waiting for busy
|
||||
elif self.isDriving(status) and status != self._status_before_change:
|
||||
self.log.debug('time needed to change to busy: %.3g', now - self._last_change)
|
||||
self._last_change = 0
|
||||
else:
|
||||
status = (self.Status.BUSY, 'changed target')
|
||||
# BUSY can not reliably be determined from the status code, we have to do it on our own
|
||||
if abs(value - self.target) < 0.1:
|
||||
self._last_target = self.target
|
||||
if not self._within_target:
|
||||
self._within_target = time.time()
|
||||
if time.time() > self._within_target + 1:
|
||||
if status[0] != self.Status.IDLE:
|
||||
status = (self.Status.IDLE, status[1])
|
||||
elif status[0] != self.Status.BUSY:
|
||||
status = (self.Status.BUSY, status[1])
|
||||
if self._stopped:
|
||||
# combine 'stopped' with current status text
|
||||
if status[0] == self.Status.IDLE:
|
||||
status = (status[0], 'stopped')
|
||||
else:
|
||||
status = (status[0], 'stopping (%s)' % status[1])
|
||||
self.status = status
|
||||
|
||||
def write_target(self, target):
|
||||
self._stopped = False
|
||||
self._last_change = 0
|
||||
self._status_before_change = self.status
|
||||
self.status = (self.Status.BUSY, 'changed target')
|
||||
self._write_params(target, self.speed)
|
||||
return Done
|
||||
|
||||
def write_speed(self, value):
|
||||
if self.isDriving():
|
||||
self._write_params(self.target, value)
|
||||
return Done
|
||||
self.speed = value
|
||||
return None # do not execute MOVE command, as this would trigger an unnecessary move
|
||||
|
||||
def stop(self):
|
||||
if not self.isDriving():
|
||||
return
|
||||
newtarget = clamp(self._last_target, self.value, self.target)
|
||||
if newtarget != self.target:
|
||||
self.log.debug('stop at %s T', newtarget)
|
||||
self.write_target(newtarget)
|
||||
self.status = (self.status[0], 'stopping (%s)' % self.status[1])
|
||||
self._stopped = True
|
237
frappy_psi/ppmssim.py
Normal file
237
frappy_psi/ppmssim.py
Normal file
@ -0,0 +1,237 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
import json
|
||||
import math
|
||||
import time
|
||||
|
||||
|
||||
def num(string):
|
||||
return json.loads(string)
|
||||
|
||||
|
||||
class NamedList:
|
||||
def __init__(self, keys, *args, **kwargs):
|
||||
self.__keys__ = keys.split()
|
||||
self.setvalues(args)
|
||||
for key, val in kwargs.items():
|
||||
setattr(self, key, val)
|
||||
|
||||
def setvalues(self, values):
|
||||
for key, arg in zip(self.__keys__, values):
|
||||
setattr(self, key, arg)
|
||||
|
||||
def aslist(self):
|
||||
return [getattr(self, key) for key in self.__keys__]
|
||||
|
||||
def __getitem__(self, index):
|
||||
return getattr(self, self.__keys__[index])
|
||||
|
||||
def __setitem__(self, index, value):
|
||||
return setattr(self, self.__keys__[index], value)
|
||||
|
||||
def __repr__(self):
|
||||
return ",".join("%.7g" % val for val in self.aslist())
|
||||
|
||||
|
||||
class PpmsSim:
|
||||
CHANNELS = {
|
||||
0: 'st', 1: 't', 2: 'mf', 3: 'pos', 4: 'r1', 5: 'i1', 6: 'r2', 7: 'i2',
|
||||
23: 'ts',
|
||||
}
|
||||
|
||||
def __init__(self):
|
||||
self.status = NamedList('t mf ch pos', 1, 1, 1, 1)
|
||||
self.st = 0x1111
|
||||
self.t = 15
|
||||
self.temp = NamedList('target ramp amode', 200., 1, 0, fast=self.t, delay=10)
|
||||
self.mf = 100
|
||||
self.field = NamedList('target ramp amode pmode', 0, 50, 0, 0)
|
||||
self.pos = 0
|
||||
self.move = NamedList('target mode code', 0, 0, 0)
|
||||
self.chamber = NamedList('target', 0)
|
||||
self.level = NamedList('value code', 100.0, 1)
|
||||
self.bridge1 = NamedList('no exc pow dc mode vol', 1, 333, 1000, 0, 2, 1)
|
||||
self.bridge2 = NamedList('no exc pow dc mode vol', 2, 333, 1000, 0, 2, 1)
|
||||
self.bridge3 = NamedList('no exc pow dc mode vol', 3, 333, 1000, 0, 2, 1)
|
||||
self.bridge4 = NamedList('no exc pow dc mode vol', 4, 333, 1000, 0, 2, 1)
|
||||
self.drvout1 = NamedList('no cur pow', 1, 333, 1000)
|
||||
self.drvout2 = NamedList('no cur pow', 2, 333, 1000)
|
||||
self.r1 = 0
|
||||
self.i1 = 0
|
||||
self.r2 = 0
|
||||
self.i2 = 0
|
||||
self.ts = self.t + 0.1
|
||||
self.time = int(time.time())
|
||||
self.start = self.time
|
||||
self.mf_start = 0
|
||||
self.ch_start = 0
|
||||
self.t_start = 0
|
||||
self.changed = set()
|
||||
|
||||
def progress(self):
|
||||
now = time.time()
|
||||
if self.time >= now:
|
||||
return
|
||||
while self.time < now:
|
||||
self.time += 1
|
||||
if self.temp.amode: # no overshoot
|
||||
dif = self.temp.target - self.temp.fast
|
||||
else:
|
||||
dif = self.temp.target - self.t
|
||||
self.temp.fast += math.copysign(min(self.temp.ramp / 60.0, abs(dif)), dif)
|
||||
self.t += (self.temp.fast - self.t) / self.temp.delay
|
||||
|
||||
# handle magnetic field
|
||||
if 'FIELD' in self.changed:
|
||||
self.changed.remove('FIELD')
|
||||
if self.field.target < 0:
|
||||
self.status.mf = 15 # general error
|
||||
elif self.status.mf == 1: # persistent
|
||||
self.mf_start = now # indicates leads are ramping
|
||||
elif self.status.mf == 3: # switch_cooling
|
||||
self.mf_start = now
|
||||
self.status.mf = 2 # switch_warming
|
||||
else:
|
||||
self.status.mf = 6 + int(self.field.target < self.mf) # charging or discharging
|
||||
if self.status.mf == 1 and self.mf_start: # leads ramping
|
||||
if now > self.mf_start + abs(self.field.target) / 10000 + 5:
|
||||
self.mf_start = now
|
||||
self.status.mf = 2 # switch_warming
|
||||
elif self.status.mf == 2: # switch_warming
|
||||
if now > self.mf_start + 15:
|
||||
self.status.mf = 6 + int(self.field.target < self.mf) # charging or discharging
|
||||
elif self.status.mf == 5: # driven_final
|
||||
if now > self.mf_start + 5:
|
||||
self.mf_start = now
|
||||
self.status.mf = 3 # switch cooling
|
||||
elif self.status.mf == 3: # switch_cooling
|
||||
if now > self.mf_start + 15:
|
||||
self.status.mf = 1 # persistent_mode
|
||||
self.mf_start = 0 # == no leads ramping happens
|
||||
elif self.status.mf in (6, 7): # charging, discharging
|
||||
dif = self.field.target - self.mf
|
||||
if abs(dif) < 0.01:
|
||||
if self.field.pmode:
|
||||
self.status.mf = 4 # driven_stable
|
||||
else:
|
||||
self.status.mf = 5 # driven_final
|
||||
self.mf_last = now
|
||||
else:
|
||||
self.mf += math.copysign(min(self.field.ramp, abs(dif)), dif)
|
||||
# print(self.mf, self.status.mf, self.field)
|
||||
|
||||
dif = self.move.target - self.pos
|
||||
speed = (15 - self.move.code) * 0.8
|
||||
self.pos += math.copysign(min(speed, abs(dif)), dif)
|
||||
|
||||
if 'CHAMBER' in self.changed:
|
||||
self.changed.remove('CHAMBER')
|
||||
if self.chamber.target == 0: # seal immediately
|
||||
self.status.ch = 3 # sealed unknown
|
||||
self.ch_start = 0
|
||||
elif self.chamber.target == 3: # pump cont.
|
||||
self.status.ch = 8
|
||||
self.ch_start = 0
|
||||
elif self.chamber.target == 4: # vent cont.
|
||||
self.status.ch = 9
|
||||
self.ch_start = 0
|
||||
elif self.chamber.target == 1: # purge and seal
|
||||
self.status.ch = 4
|
||||
self.ch_start = now
|
||||
elif self.chamber.target == 2: # vent and seal
|
||||
self.status.ch = 5
|
||||
self.ch_start = now
|
||||
elif self.chamber.target == 5: # hi vac.
|
||||
self.status.ch = 6 # pumping down
|
||||
self.ch_start = now
|
||||
elif self.ch_start and now > self.ch_start + 15:
|
||||
self.ch_start = 0
|
||||
if self.chamber.target == 5:
|
||||
self.status.ch = 7 # at high vac.
|
||||
else:
|
||||
self.status.ch = self.chamber.target
|
||||
|
||||
if 'TEMP' in self.changed:
|
||||
self.changed.remove('TEMP')
|
||||
self.status.t = 2 # changing
|
||||
self.t_start = now
|
||||
elif abs(self.t - self.temp.target) < 0.1:
|
||||
if now > self.t_start + 10:
|
||||
self.status.t = 1 # stable
|
||||
else:
|
||||
self.status.t = 5 # within tolerance
|
||||
else:
|
||||
self.t_start = now
|
||||
if abs(self.t - self.temp.target) < 1:
|
||||
self.status.t = 6 # outside tolerance
|
||||
|
||||
if abs(self.pos - self.move.target) < 0.01:
|
||||
self.status.pos = 1
|
||||
else:
|
||||
self.status.pos = 5
|
||||
|
||||
self.st = sum(self.status[i] << (i * 4) for i in range(4))
|
||||
self.r1 = self.t * 0.1
|
||||
self.i1 = self.t % 10.0
|
||||
self.r2 = 1000 / self.t
|
||||
self.i2 = math.log(self.t)
|
||||
self.ts = self.t + 0.1
|
||||
self.level.value = 100 - (self.time - self.start) * 0.01 % 100
|
||||
|
||||
def getdat(self, mask):
|
||||
mask = int(mask) & 0x8000ff # all channels up to i2 plus ts
|
||||
output = ['%d' % mask, '%.2f' % (time.time() - self.start)]
|
||||
for i, chan in self.CHANNELS.items():
|
||||
if (1 << i) & mask:
|
||||
output.append("%.7g" % getattr(self, chan))
|
||||
return ",".join(output)
|
||||
|
||||
|
||||
class QDevice:
|
||||
def __init__(self, classid):
|
||||
self.sim = PpmsSim()
|
||||
|
||||
def send(self, command):
|
||||
self.sim.progress()
|
||||
if '?' in command:
|
||||
if command.startswith('GETDAT?'):
|
||||
mask = int(command[7:])
|
||||
result = self.sim.getdat(mask)
|
||||
else:
|
||||
name, args = command.split('?')
|
||||
name += args.strip()
|
||||
result = getattr(self.sim, name.lower()).aslist()
|
||||
result = ",".join("%.7g" % arg for arg in result)
|
||||
# print(command, '/', result)
|
||||
else:
|
||||
# print(command)
|
||||
name, args = command.split()
|
||||
args = json.loads("[%s]" % args)
|
||||
if name.startswith('BRIDGE') or name.startswith('DRVOUT'):
|
||||
name = name + str(int(args[0]))
|
||||
getattr(self.sim, name.lower()).setvalues(args)
|
||||
self.sim.changed.add(name)
|
||||
result = "OK"
|
||||
return result
|
||||
|
||||
|
||||
def shutdown():
|
||||
pass
|
66
frappy_psi/ppmswindows.py
Normal file
66
frappy_psi/ppmswindows.py
Normal file
@ -0,0 +1,66 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
import threading
|
||||
|
||||
try:
|
||||
import pythoncom
|
||||
import win32com.client
|
||||
except ImportError:
|
||||
print("This Module only works with a pythoncom module on a MS Windows OS")
|
||||
raise
|
||||
|
||||
|
||||
class Error(Exception):
|
||||
pass
|
||||
|
||||
|
||||
class QDevice:
|
||||
def __init__(self, classid):
|
||||
self.threadlocal = threading.local()
|
||||
self.classid = classid
|
||||
|
||||
def send(self, command):
|
||||
try:
|
||||
mvu = self.threadlocal.mvu
|
||||
except AttributeError:
|
||||
pythoncom.CoInitialize()
|
||||
mvu = win32com.client.Dispatch(self.classid)
|
||||
self.threadlocal.mvu = mvu
|
||||
args = [
|
||||
win32com.client.VARIANT(pythoncom.VT_BYREF | pythoncom.VT_BSTR, command),
|
||||
win32com.client.VARIANT(pythoncom.VT_BYREF | pythoncom.VT_BSTR, ""), # reply
|
||||
win32com.client.VARIANT(pythoncom.VT_BYREF | pythoncom.VT_BSTR, ""), # error
|
||||
win32com.client.VARIANT(pythoncom.VT_BYREF | pythoncom.VT_I4, 0), # ?
|
||||
win32com.client.VARIANT(pythoncom.VT_BYREF | pythoncom.VT_I4, 0)] # ?
|
||||
err = mvu.SendPpmsCommand(*args)
|
||||
# win32com does invert the order of results!
|
||||
if err == 0:
|
||||
# print '<', args[3].value
|
||||
return args[3].value
|
||||
if err == 1:
|
||||
# print '<done'
|
||||
return "OK"
|
||||
raise Error('%s on cmd "%s" %s' % (args[2].value.replace('\n', ' '), command,
|
||||
getattr(args[2], 'value', 'noreply')))
|
||||
|
||||
|
||||
if __name__ == "__main__": # test only
|
||||
print(QDevice('QD.MULTIVU.PPMS.1').send('LEVEL?'))
|
230
frappy_psi/softcal.py
Normal file
230
frappy_psi/softcal.py
Normal file
@ -0,0 +1,230 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
# *****************************************************************************
|
||||
"""Software calibration"""
|
||||
|
||||
import math
|
||||
import os
|
||||
from os.path import basename, dirname, exists, join
|
||||
|
||||
import numpy as np
|
||||
from scipy.interpolate import splev, splrep # pylint: disable=import-error
|
||||
|
||||
from frappy.core import Attached, BoolType, Parameter, Readable, StringType, \
|
||||
FloatRange, Done
|
||||
|
||||
|
||||
def linear(x):
|
||||
return x
|
||||
|
||||
|
||||
nplog = np.vectorize(math.log10)
|
||||
npexp = np.vectorize(lambda x: 10 ** x)
|
||||
|
||||
|
||||
class StdParser:
|
||||
"""parser used for reading columns"""
|
||||
def __init__(self, **kwds):
|
||||
"""keys may be other 'x' or 'logx' and either 'y' or 'logy'
|
||||
|
||||
default is x=0, y=1
|
||||
"""
|
||||
self.xcol = int(kwds.get('x', kwds.get('logx', 0)))
|
||||
self.ycol = int(kwds.get('y', kwds.get('logy', 1)))
|
||||
self.logx = 'logx' in kwds
|
||||
self.logy = 'logy' in kwds
|
||||
self.xdata, self.ydata = [], []
|
||||
|
||||
def parse(self, line):
|
||||
"""get numbers from a line and put them to self.xdata / self.ydata"""
|
||||
row = line.split()
|
||||
try:
|
||||
self.xdata.append(float(row[self.xcol]))
|
||||
self.ydata.append(float(row[self.ycol]))
|
||||
except (IndexError, ValueError):
|
||||
# skip bad lines
|
||||
return
|
||||
|
||||
|
||||
class Parser340(StdParser):
|
||||
"""parser for LakeShore *.340 files"""
|
||||
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
self.header = True
|
||||
self.xcol, self.ycol = 1, 2
|
||||
self.logx, self.logy = False, False
|
||||
|
||||
def parse(self, line):
|
||||
"""scan header for data format"""
|
||||
if self.header:
|
||||
key, _, value = line.partition(':')
|
||||
if value: # this is a header line, as it contains ':'
|
||||
value = value.split()[0]
|
||||
key = ''.join(key.split()).lower()
|
||||
if key == 'dataformat':
|
||||
if value == '4':
|
||||
self.logx, self.logy = True, False # logOhm
|
||||
elif value == '5':
|
||||
self.logx, self.logy = True, True # logOhm, logK
|
||||
elif value not in ('1', '2', '3'):
|
||||
raise ValueError('invalid Data Format')
|
||||
elif 'No.' in line:
|
||||
self.header = False
|
||||
return
|
||||
super().parse(line)
|
||||
|
||||
|
||||
KINDS = {
|
||||
"340": (Parser340, {}), # lakeshore 340 format
|
||||
"inp": (StdParser, {}), # M. Zollikers *.inp calcurve format
|
||||
"caldat": (StdParser, dict(x=1, y=2)), # format from sea/tcl/startup/calib_ext.tcl
|
||||
"dat": (StdParser, {}), # lakeshore raw data *.dat format
|
||||
}
|
||||
|
||||
|
||||
class CalCurve:
|
||||
def __init__(self, calibspec):
|
||||
"""calibspec format:
|
||||
[<full path> | <name>][,<key>=<value> ...]
|
||||
for <key>/<value> as in parser arguments
|
||||
"""
|
||||
sensopt = calibspec.split(',')
|
||||
calibname = sensopt.pop(0)
|
||||
_, dot, ext = basename(calibname).rpartition('.')
|
||||
kind = None
|
||||
pathlist = os.environ.get('FRAPPY_CALIB_PATH', '').split(',')
|
||||
pathlist.append(join(dirname(__file__), 'calcurves'))
|
||||
for path in pathlist:
|
||||
# first try without adding kind
|
||||
filename = join(path.strip(), calibname)
|
||||
if exists(filename):
|
||||
kind = ext if dot else None
|
||||
break
|
||||
# then try adding all kinds as extension
|
||||
for nam in calibname, calibname.upper(), calibname.lower():
|
||||
for kind in KINDS:
|
||||
filename = join(path.strip(), '%s.%s' % (nam, kind))
|
||||
if exists(filename):
|
||||
break
|
||||
else:
|
||||
continue
|
||||
break
|
||||
else:
|
||||
continue
|
||||
break
|
||||
else:
|
||||
raise FileNotFoundError(calibname)
|
||||
optargs = {}
|
||||
for opts in sensopt:
|
||||
key, _, value = opts.lower().rpartition('=')
|
||||
value = value.strip()
|
||||
if value:
|
||||
optargs[key.strip()] = value
|
||||
kind = optargs.pop('kind', kind)
|
||||
cls, args = KINDS.get(kind, (StdParser, {}))
|
||||
args.update(optargs)
|
||||
|
||||
try:
|
||||
parser = cls(**args)
|
||||
with open(filename, encoding='utf-8') as f:
|
||||
for line in f:
|
||||
parser.parse(line)
|
||||
except Exception as e:
|
||||
raise ValueError('calib curve %s: %s' % (calibspec, e)) from e
|
||||
self.convert_x = nplog if parser.logx else linear
|
||||
self.convert_y = npexp if parser.logy else linear
|
||||
x = np.asarray(parser.xdata)
|
||||
y = np.asarray(parser.ydata)
|
||||
if np.all(x[:-1] > x[1:]): # all decreasing
|
||||
x = np.flip(x)
|
||||
y = np.flip(y)
|
||||
elif np.any(x[:-1] >= x[1:]): # some not increasing
|
||||
raise ValueError('calib curve %s is not monotonic' % calibspec)
|
||||
try:
|
||||
self.spline = splrep(x, y, s=0, k=min(3, len(x) - 1))
|
||||
except (ValueError, TypeError) as e:
|
||||
raise ValueError('invalid calib curve %s' % calibspec) from e
|
||||
|
||||
def __call__(self, value):
|
||||
"""convert value
|
||||
|
||||
value might be a single value or an numpy array
|
||||
"""
|
||||
result = splev(self.convert_x(value), self.spline)
|
||||
return self.convert_y(result)
|
||||
|
||||
|
||||
class Sensor(Readable):
|
||||
rawsensor = Attached()
|
||||
|
||||
calib = Parameter('calibration name', datatype=StringType(), readonly=False)
|
||||
abs = Parameter('True: take abs(raw) before calib', datatype=BoolType(), readonly=False, default=True)
|
||||
value = Parameter(datatype=FloatRange(unit='K'))
|
||||
pollinterval = Parameter(export=False)
|
||||
status = Parameter(default=(Readable.Status.ERROR, 'unintialized'))
|
||||
|
||||
description = 'a calibrated sensor value'
|
||||
_value_error = None
|
||||
|
||||
def checkProperties(self):
|
||||
if 'description' not in self.propertyValues:
|
||||
self.description = '_' # avoid complaining about missing description
|
||||
super().checkProperties()
|
||||
|
||||
def initModule(self):
|
||||
super().initModule()
|
||||
self.rawsensor.registerCallbacks(self, ['status']) # auto update status
|
||||
self._calib = CalCurve(self.calib)
|
||||
if self.description == '_':
|
||||
self.description = '%r calibrated with curve %r' % (self.rawsensor, self.calib)
|
||||
|
||||
def doPoll(self):
|
||||
self.read_status()
|
||||
|
||||
def write_calib(self, value):
|
||||
self._calib = CalCurve(value)
|
||||
return value
|
||||
|
||||
def update_value(self, value):
|
||||
if self.abs:
|
||||
value = abs(float(value))
|
||||
self.value = self._calib(value)
|
||||
self._value_error = None
|
||||
|
||||
def error_update_value(self, err):
|
||||
if self.abs and str(err) == 'R_UNDER': # hack: ignore R_UNDER from ls370
|
||||
self._value_error = None
|
||||
return None
|
||||
self._value_error = repr(err)
|
||||
raise err
|
||||
|
||||
def update_status(self, value):
|
||||
if self._value_error is None:
|
||||
self.status = value
|
||||
else:
|
||||
self.status = self.Status.ERROR, self._value_error
|
||||
|
||||
def read_value(self):
|
||||
return self._calib(self.rawsensor.read_value())
|
||||
|
||||
def read_status(self):
|
||||
self.update_status(self.rawsensor.status)
|
||||
return Done
|
447
frappy_psi/trinamic.py
Normal file
447
frappy_psi/trinamic.py
Normal file
@ -0,0 +1,447 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
# *****************************************************************************
|
||||
#
|
||||
# This program is free software; you can redistribute it and/or modify it under
|
||||
# the terms of the GNU General Public License as published by the Free Software
|
||||
# Foundation; either version 2 of the License, or (at your option) any later
|
||||
# version.
|
||||
#
|
||||
# This program is distributed in the hope that it will be useful, but WITHOUT
|
||||
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
|
||||
# FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
|
||||
# details.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License along with
|
||||
# this program; if not, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#
|
||||
# Module authors:
|
||||
# Markus Zolliker <markus.zolliker@psi.ch>
|
||||
#
|
||||
# *****************************************************************************
|
||||
|
||||
"""drivers for trinamic PD-1161 motors"""
|
||||
|
||||
import time
|
||||
import struct
|
||||
|
||||
from frappy.core import BoolType, Command, EnumType, FloatRange, IntRange, \
|
||||
HasIO, Parameter, Property, Drivable, PersistentMixin, PersistentParam, Done, \
|
||||
IDLE, BUSY, ERROR
|
||||
from frappy.io import BytesIO
|
||||
from frappy.errors import CommunicationFailedError, HardwareError, BadValueError, IsBusyError
|
||||
from frappy.rwhandler import ReadHandler, WriteHandler
|
||||
from frappy.lib import formatStatusBits
|
||||
|
||||
MOTOR_STOP = 3
|
||||
MOVE = 4
|
||||
SET_AXIS_PAR = 5
|
||||
GET_AXIS_PAR = 6
|
||||
SET_GLOB_PAR = 9
|
||||
GET_GLOB_PAR = 10
|
||||
SET_IO = 14
|
||||
GET_IO = 15
|
||||
# STORE_GLOB_PAR = 11
|
||||
|
||||
BAUDRATES = [9600, 0, 19200, 0, 38400, 57600, 0, 115200]
|
||||
|
||||
FULL_STEP = 1.8
|
||||
ANGLE_SCALE = FULL_STEP/256
|
||||
# assume factory settings for pulse and ramp divisors:
|
||||
SPEED_SCALE = 1E6 / 2 ** 15 * ANGLE_SCALE
|
||||
MAX_SPEED = 2047 * SPEED_SCALE
|
||||
ACCEL_SCALE = 1E12 / 2 ** 31 * ANGLE_SCALE
|
||||
MAX_ACCEL = 2047 * ACCEL_SCALE
|
||||
CURRENT_SCALE = 2.8/250
|
||||
ENCODER_RESOLUTION = 360 / 1024
|
||||
|
||||
HW_ARGS = {
|
||||
# <parameter name>: (address, scale factor)
|
||||
'encoder_tolerance': (212, ANGLE_SCALE),
|
||||
'speed': (4, SPEED_SCALE),
|
||||
'minspeed': (130, SPEED_SCALE),
|
||||
'currentspeed': (3, SPEED_SCALE),
|
||||
'maxcurrent': (6, CURRENT_SCALE),
|
||||
'standby_current': (7, CURRENT_SCALE,),
|
||||
'acceleration': (5, ACCEL_SCALE),
|
||||
'target_reached': (8, 1),
|
||||
'move_status': (207, 1),
|
||||
'error_bits': (208, 1),
|
||||
'free_wheeling': (204, 0.01),
|
||||
'power_down_delay': (214, 0.01),
|
||||
}
|
||||
|
||||
# special handling (adjust zero):
|
||||
ENCODER_ADR = 209
|
||||
STEPPOS_ADR = 1
|
||||
|
||||
|
||||
def writable(*args, **kwds):
|
||||
"""convenience function to create writable hardware parameters"""
|
||||
return PersistentParam(*args, readonly=False, initwrite=True, **kwds)
|
||||
|
||||
|
||||
class Motor(PersistentMixin, HasIO, Drivable):
|
||||
address = Property('module address', IntRange(0, 255), default=1)
|
||||
|
||||
value = Parameter('motor position', FloatRange(unit='deg', fmtstr='%.3f'),
|
||||
needscfg=False)
|
||||
zero = PersistentParam('zero point', FloatRange(unit='$'), readonly=False, default=0)
|
||||
encoder = PersistentParam('encoder reading', FloatRange(unit='$', fmtstr='%.1f'),
|
||||
readonly=True, initwrite=False)
|
||||
steppos = PersistentParam('position from motor steps', FloatRange(unit='$', fmtstr='%.3f'),
|
||||
readonly=True, initwrite=False)
|
||||
target = Parameter('', FloatRange(unit='$'), default=0)
|
||||
|
||||
move_limit = Parameter('max. angle to drive in one go when current above safe_current',
|
||||
FloatRange(unit='$'),
|
||||
readonly=False, default=360, group='more')
|
||||
safe_current = Parameter('motor current allowed for big steps', FloatRange(unit='A'),
|
||||
readonly=False, default=0.2, group='more')
|
||||
tolerance = Parameter('positioning tolerance', FloatRange(unit='$'),
|
||||
readonly=False, default=0.9)
|
||||
encoder_tolerance = writable('the allowed deviation between steppos and encoder\n\nmust be > tolerance',
|
||||
FloatRange(0, 360., unit='$', fmtstr='%.3f'), group='more')
|
||||
has_encoder = Parameter('whether encoder is used or not', BoolType(),
|
||||
readonly=False, default=True, group='more')
|
||||
speed = writable('max. speed', FloatRange(0, MAX_SPEED, unit='$/sec', fmtstr='%.1f'), default=40)
|
||||
minspeed = writable('min. speed', FloatRange(0, MAX_SPEED, unit='$/sec', fmtstr='%.1f'),
|
||||
default=SPEED_SCALE, group='motorparam')
|
||||
currentspeed = Parameter('current speed', FloatRange(-MAX_SPEED, MAX_SPEED, unit='$/sec', fmtstr='%.1f'),
|
||||
group='motorparam')
|
||||
maxcurrent = writable('', FloatRange(0, 2.8, unit='A', fmtstr='%.2f'),
|
||||
default=1.4, group='motorparam')
|
||||
standby_current = writable('', FloatRange(0, 2.8, unit='A', fmtstr='%.2f'),
|
||||
default=0.1, group='motorparam')
|
||||
acceleration = writable('', FloatRange(4.6 * ACCEL_SCALE, MAX_ACCEL, unit='deg/s^2', fmtstr='%.1f'),
|
||||
default=150., group='motorparam')
|
||||
target_reached = Parameter('', BoolType(), group='hwstatus')
|
||||
move_status = Parameter('', EnumType(ok=0, stalled=1, encoder_deviation=2, stalled_and_encoder_deviation=3),
|
||||
group='hwstatus')
|
||||
error_bits = Parameter('', IntRange(0, 255), group='hwstatus')
|
||||
home = Parameter('state of home switch (input 3)', BoolType())
|
||||
has_home = Parameter('enable home and activate pullup resistor', BoolType(),
|
||||
default=True, initwrite=True, group='more')
|
||||
auto_reset = Parameter('automatic reset after failure', BoolType(), readonly=False, default=False)
|
||||
free_wheeling = writable('', FloatRange(0, 60., unit='sec', fmtstr='%.2f'),
|
||||
default=0.1, group='motorparam')
|
||||
|
||||
power_down_delay = writable('', FloatRange(0, 60., unit='sec', fmtstr='%.2f'),
|
||||
default=0.1, group='motorparam')
|
||||
baudrate = Parameter('', EnumType({'%d' % v: i for i, v in enumerate(BAUDRATES)}),
|
||||
readonly=False, default=0, visibility=3, group='more')
|
||||
pollinterval = Parameter(group='more')
|
||||
|
||||
ioClass = BytesIO
|
||||
fast_poll = 0.05
|
||||
_run_mode = 0 # 0: idle, 1: driving, 2: stopping
|
||||
_calc_timeout = True
|
||||
_need_reset = None
|
||||
_last_change = 0
|
||||
_loading = False # True when loading parameters
|
||||
|
||||
def comm(self, cmd, adr, value=0, bank=0):
|
||||
"""set or get a parameter
|
||||
|
||||
:param adr: parameter number
|
||||
:param cmd: instruction number (SET_* or GET_*)
|
||||
:param bank: the bank
|
||||
:param value: if given, the parameter is written, else it is returned
|
||||
:return: the returned value
|
||||
"""
|
||||
if self._calc_timeout and self.io._conn:
|
||||
self._calc_timeout = False
|
||||
baudrate = getattr(self.io._conn.connection, 'baudrate', None)
|
||||
if baudrate:
|
||||
if baudrate not in BAUDRATES:
|
||||
raise CommunicationFailedError('unsupported baud rate: %d' % baudrate)
|
||||
self.io.timeout = 0.03 + 200 / baudrate
|
||||
|
||||
exc = None
|
||||
byt = struct.pack('>BBBBi', self.address, cmd, adr, bank, round(value))
|
||||
byt += bytes([sum(byt) & 0xff])
|
||||
for itry in range(3,0,-1):
|
||||
try:
|
||||
reply = self.communicate(byt, 9)
|
||||
if sum(reply[:-1]) & 0xff != reply[-1]:
|
||||
raise CommunicationFailedError('checksum error')
|
||||
# will try again
|
||||
except Exception as e:
|
||||
if itry == 1:
|
||||
raise
|
||||
exc = e
|
||||
continue
|
||||
break
|
||||
if exc:
|
||||
self.log.warning('tried %d times after %s', itry, exc)
|
||||
radr, modadr, status, rcmd, result = struct.unpack('>BBBBix', reply)
|
||||
if status != 100:
|
||||
self.log.warning('bad status from cmd %r %s: %d', cmd, adr, status)
|
||||
if radr != 2 or modadr != self.address or cmd != rcmd:
|
||||
raise CommunicationFailedError('bad reply %r to command %s %d' % (reply, cmd, adr))
|
||||
return result
|
||||
|
||||
def startModule(self, start_events):
|
||||
super().startModule(start_events)
|
||||
|
||||
def fix_encoder(self=self):
|
||||
if not self.has_encoder:
|
||||
return
|
||||
try:
|
||||
# get encoder value from motor. at this stage self.encoder contains the persistent value
|
||||
encoder = self._read_axispar(ENCODER_ADR, ANGLE_SCALE) + self.zero
|
||||
self.fix_encoder(encoder)
|
||||
except Exception as e:
|
||||
self.log.error('fix_encoder failed with %r', e)
|
||||
|
||||
if self.has_encoder:
|
||||
start_events.queue(fix_encoder)
|
||||
|
||||
def fix_encoder(self, encoder_from_hw):
|
||||
"""fix encoder value
|
||||
|
||||
:param encoder_from_hw: the encoder value read from the HW
|
||||
|
||||
self.encoder is assumed to contain the last known (persistent) value
|
||||
if encoder has not changed modulo 360, adjust by an integer multiple of 360
|
||||
set status to error when encoder has changed be more than encoder_tolerance
|
||||
"""
|
||||
# calculate nearest, most probable value
|
||||
adjusted_encoder = encoder_from_hw + round((self.encoder - encoder_from_hw) / 360.) * 360
|
||||
if abs(self.encoder - adjusted_encoder) >= self.encoder_tolerance:
|
||||
# encoder modulo 360 has changed
|
||||
self.log.error('saved encoder value (%.2f) does not match reading (%.2f %.2f)',
|
||||
self.encoder, encoder_from_hw, adjusted_encoder)
|
||||
if adjusted_encoder != encoder_from_hw:
|
||||
self.log.info('take next closest encoder value (%.2f)' % adjusted_encoder)
|
||||
self._need_reset = True
|
||||
self.status = ERROR, 'saved encoder value does not match reading'
|
||||
self._write_axispar(adjusted_encoder - self.zero, ENCODER_ADR, ANGLE_SCALE, readback=False)
|
||||
|
||||
def _read_axispar(self, adr, scale=1):
|
||||
value = self.comm(GET_AXIS_PAR, adr)
|
||||
# do not apply scale when 1 (datatype might not be float)
|
||||
return value if scale == 1 else value * scale
|
||||
|
||||
def _write_axispar(self, value, adr, scale=1, readback=True):
|
||||
rawvalue = round(value / scale)
|
||||
self.comm(SET_AXIS_PAR, adr, rawvalue)
|
||||
if readback:
|
||||
result = self.comm(GET_AXIS_PAR, adr)
|
||||
if result != rawvalue:
|
||||
raise HardwareError('result for adr=%d scale=%g does not match %g != %g'
|
||||
% (adr, scale, result * scale, value))
|
||||
return result * scale
|
||||
return rawvalue * scale
|
||||
|
||||
@ReadHandler(HW_ARGS)
|
||||
def read_hwparam(self, pname):
|
||||
"""handle read for HwParam"""
|
||||
args = HW_ARGS[pname]
|
||||
reply = self._read_axispar(*args)
|
||||
try:
|
||||
value = getattr(self, pname)
|
||||
except Exception:
|
||||
return reply
|
||||
if reply != value:
|
||||
if not self.parameters[pname].readonly:
|
||||
# this should not happen
|
||||
self.log.warning('hw parameter %s has changed from %r to %r, write again', pname, value, reply)
|
||||
self._write_axispar(value, *args, readback=False)
|
||||
reply = self._read_axispar(*args)
|
||||
return reply
|
||||
|
||||
@WriteHandler(HW_ARGS)
|
||||
def write_hwparam(self, pname, value):
|
||||
"""handler write for HwParam"""
|
||||
return self._write_axispar(value, *HW_ARGS[pname])
|
||||
|
||||
def doPoll(self):
|
||||
self.read_status() # read_value is called by read_status
|
||||
|
||||
def read_value(self):
|
||||
steppos = self.read_steppos()
|
||||
encoder = self.read_encoder() if self.has_encoder else steppos
|
||||
if self.has_home:
|
||||
self.read_home()
|
||||
initialized = self.comm(GET_GLOB_PAR, 255, bank=2)
|
||||
if initialized: # no power loss
|
||||
self.saveParameters()
|
||||
elif not self._loading: # just powered up
|
||||
try:
|
||||
self._loading = True
|
||||
# get persistent values
|
||||
writeDict = self.loadParameters()
|
||||
finally:
|
||||
self._loading = False
|
||||
self.log.info('set to previous saved values %r', writeDict)
|
||||
# self.encoder now contains the last known (persistent) value
|
||||
if self._need_reset is None:
|
||||
if self.status[0] == IDLE:
|
||||
# server started, power cycled and encoder value matches last one
|
||||
self.reset()
|
||||
else:
|
||||
if self.has_encoder:
|
||||
self.fix_encoder(encoder)
|
||||
self._need_reset = True
|
||||
self.status = ERROR, 'power loss'
|
||||
# or should we just fix instead of error status?
|
||||
# self._write_axispar(self.steppos - self.zero, readback=False)
|
||||
self.comm(SET_GLOB_PAR, 255, 1, bank=2) # set initialized flag
|
||||
self._run_mode = 0
|
||||
self.setFastPoll(False)
|
||||
|
||||
return encoder if abs(encoder - steppos) > self.tolerance else steppos
|
||||
|
||||
def read_status(self):
|
||||
oldpos = self.steppos
|
||||
self.read_value() # make sure encoder and steppos are fresh
|
||||
if not self._run_mode:
|
||||
if self.has_encoder and abs(self.encoder - self.steppos) > self.encoder_tolerance:
|
||||
self._need_reset = True
|
||||
if self.auto_reset:
|
||||
return IDLE, 'encoder does not match internal pos'
|
||||
if self.status[0] != ERROR:
|
||||
self.log.error('encoder (%.2f) does not match internal pos (%.2f)', self.encoder, self.steppos)
|
||||
return ERROR, 'encoder does not match internal pos'
|
||||
return self.status
|
||||
now = self.parameters['steppos'].timestamp
|
||||
if self.steppos != oldpos:
|
||||
self._last_change = now
|
||||
return BUSY, 'stopping' if self._run_mode == 2 else 'moving'
|
||||
if now < self._last_change + 0.3 and not (self.read_target_reached() or self.read_move_status()):
|
||||
return BUSY, 'stopping' if self._run_mode == 2 else 'moving'
|
||||
if self.target_reached:
|
||||
reason = ''
|
||||
elif self.move_status:
|
||||
reason = self.move_status.name
|
||||
elif self.error_bits:
|
||||
reason = formatStatusBits(self.error_bits, (
|
||||
'stallGuard', 'over_temp', 'over_temp_warn', 'short_A', 'short_B',
|
||||
'open_load_A', 'open_load_B', 'standstill'))
|
||||
else:
|
||||
reason = 'unknown'
|
||||
self.setFastPoll(False)
|
||||
if self._run_mode == 2:
|
||||
self.target = self.value # indicate to customers that this was stopped
|
||||
self._run_mode = 0
|
||||
return IDLE, 'stopped'
|
||||
self._run_mode = 0
|
||||
diff = self.target - self.encoder
|
||||
if abs(diff) <= self.tolerance:
|
||||
if reason:
|
||||
self.log.warning('target reached, but move_status = %s', reason)
|
||||
return IDLE, ''
|
||||
if self.auto_reset:
|
||||
self._need_reset = True
|
||||
return IDLE, 'stalled: %s' % reason
|
||||
self.log.error('out of tolerance by %.3g (%s)', diff, reason)
|
||||
return ERROR, 'out of tolerance (%s)' % reason
|
||||
|
||||
def write_target(self, target):
|
||||
for _ in range(2): # for auto reset
|
||||
self.read_value() # make sure encoder and steppos are fresh
|
||||
if self.maxcurrent >= self.safe_current + CURRENT_SCALE and (
|
||||
abs(target - self.encoder) > self.move_limit + self.tolerance):
|
||||
# pylint: disable=bad-string-format-type
|
||||
# pylint wrongly does not recognise encoder as a descriptor
|
||||
raise BadValueError('can not move more than %g deg (%g -> %g)' %
|
||||
(self.move_limit, self.encoder, target))
|
||||
diff = self.encoder - self.steppos
|
||||
if self._need_reset:
|
||||
if self.auto_reset:
|
||||
if self.isBusy():
|
||||
self.stop()
|
||||
while self.isBusy():
|
||||
time.sleep(0.1)
|
||||
self.read_value()
|
||||
self.reset()
|
||||
if self.status[0] == IDLE:
|
||||
continue
|
||||
raise HardwareError('auto reset failed')
|
||||
raise HardwareError('need reset (%s)' % self.status[1])
|
||||
break
|
||||
if abs(diff) > self.tolerance:
|
||||
if abs(diff) > self.encoder_tolerance and self.has_encoder:
|
||||
self._need_reset = True
|
||||
self.status = ERROR, 'encoder does not match internal pos'
|
||||
raise HardwareError('need reset (encoder does not match internal pos)')
|
||||
self._write_axispar(self.encoder - self.zero, STEPPOS_ADR, ANGLE_SCALE, readback=False)
|
||||
self._last_change = time.time()
|
||||
self._run_mode = 1 # driving
|
||||
self.setFastPoll(True, self.fast_poll)
|
||||
self.log.debug('move to %.1f', target)
|
||||
self.comm(MOVE, 0, (target - self.zero) / ANGLE_SCALE)
|
||||
self.status = BUSY, 'changed target'
|
||||
return target
|
||||
|
||||
def write_zero(self, value):
|
||||
self.zero = value
|
||||
self.read_value() # apply zero to encoder, steppos and value
|
||||
return Done
|
||||
|
||||
def read_encoder(self):
|
||||
if self.has_encoder:
|
||||
return self._read_axispar(ENCODER_ADR, ANGLE_SCALE) + self.zero
|
||||
return self.read_steppos()
|
||||
|
||||
def read_steppos(self):
|
||||
return self._read_axispar(STEPPOS_ADR, ANGLE_SCALE) + self.zero
|
||||
|
||||
def read_home(self):
|
||||
return not self.comm(GET_IO, 255) & 8
|
||||
|
||||
def write_has_home(self, value):
|
||||
"""activate pullup resistor"""
|
||||
return bool(self.comm(SET_IO, 0, value))
|
||||
|
||||
@Command(FloatRange())
|
||||
def set_zero(self, value):
|
||||
"""adapt zero to make current position equal to given value"""
|
||||
raw = self.read_value() - self.zero
|
||||
self.write_zero(value - raw)
|
||||
|
||||
def read_baudrate(self):
|
||||
return self.comm(GET_GLOB_PAR, 65)
|
||||
|
||||
def write_baudrate(self, value):
|
||||
"""a baudrate change takes effect only after power cycle"""
|
||||
return self.comm(SET_GLOB_PAR, 65, int(value))
|
||||
|
||||
@Command()
|
||||
def reset(self):
|
||||
"""set steppos to encoder value, if not within tolerance"""
|
||||
if self._run_mode:
|
||||
raise IsBusyError('can not reset while moving')
|
||||
tol = ENCODER_RESOLUTION * 1.1
|
||||
for itry in range(10):
|
||||
diff = self.read_encoder() - self.read_steppos()
|
||||
if abs(diff) <= tol:
|
||||
self._need_reset = False
|
||||
self.status = IDLE, 'ok'
|
||||
return
|
||||
self._write_axispar(self.encoder - self.zero, STEPPOS_ADR, ANGLE_SCALE, readback=False)
|
||||
self.comm(MOVE, 0, (self.encoder - self.zero) / ANGLE_SCALE)
|
||||
time.sleep(0.1)
|
||||
if itry > 5:
|
||||
tol = self.tolerance
|
||||
self.status = ERROR, 'reset failed'
|
||||
return
|
||||
|
||||
@Command()
|
||||
def stop(self):
|
||||
"""stop motor immediately"""
|
||||
self._run_mode = 2 # stopping
|
||||
self.comm(MOTOR_STOP, 0)
|
||||
self.status = BUSY, 'stopping'
|
||||
self.setFastPoll(False)
|
||||
|
||||
@Command(IntRange(), result=IntRange(), export=False)
|
||||
def get_axis_par(self, adr):
|
||||
"""get arbitrary motor parameter"""
|
||||
return self.comm(GET_AXIS_PAR, adr)
|
||||
|
||||
@Command((IntRange(), IntRange()), result=IntRange(), export=False)
|
||||
def set_axis_par(self, adr, value):
|
||||
"""set arbitrary motor parameter"""
|
||||
return self.comm(SET_AXIS_PAR, adr, value)
|
Reference in New Issue
Block a user