further work on needle valve, pump and lakeshore

This commit is contained in:
l_samenv 2025-03-19 16:37:27 +01:00
parent 19571ab83d
commit 41b51b35fd
10 changed files with 959 additions and 242 deletions

View File

@ -7,10 +7,10 @@ Node('ori7test.psi.ch',
rack = Rack(Mod)
with rack.lakeshore() as ls:
ls.sensor('Ts', channel='C', calcurve='x186350')
ls.loop('T', channel='B', calcurve='x174786')
ls.heater('htr', '100W', 100)
rack.lakeshore()
rack.sensor('Ts', channel='C', calcurve='x186350')
rack.loop('T', channel='B', calcurve='x174786', output_module='htr', target=10)
rack.heater('htr', 1, '100W', 25)
rack.ccu(he=True, n2=True)

View File

@ -215,7 +215,10 @@ class HasStates:
self.read_status()
if fast_poll:
sm.reset_fast_poll = True
self.setFastPoll(True)
if fast_poll is True:
self.setFastPoll(True)
else:
self.setFastPoll(True, fast_poll)
self.pollInfo.trigger(True) # trigger poller
def stop_machine(self, stopped_status=(IDLE, 'stopped')):

131
frappy_psi/autofill.py Normal file
View File

@ -0,0 +1,131 @@
# *****************************************************************************
#
# 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
from frappy.core import Attached, Readable, Writable, Parameter, Command, \
IDLE, BUSY, DISABLED, ERROR
from frappy.datatypes import FloatRange, StatusType, TupleOf, EnumType
from frappy.states import HasStates, Retry, status_code
class AutoFill(HasStates, Readable):
level = Attached(Readable)
valve = Attached(Writable)
status = Parameter(datatype=StatusType(Readable, 'BUSY'))
mode = Parameter('auto mode', EnumType(disabled=0, auto=30), readonly=False)
fill_level = Parameter('low threshold triggering start filling',
FloatRange(unit='%'), readonly=False)
full_level = Parameter('high threshold triggering stop filling',
FloatRange(unit='%'), readonly=False)
fill_minutes_range = Parameter('range of possible fill rate',
TupleOf(FloatRange(unit='min'), FloatRange(unit='min')),
readonly=False)
hold_hours_range = Parameter('range of possible consumption rate',
TupleOf(FloatRange(unit='h'), FloatRange(unit='h')),
readonly=False)
fill_delay = Parameter('delay for cooling the transfer line',
FloatRange(unit='min'), readonly=False)
def read_status(self):
if self.mode == 'DISABLED':
return DISABLED, ''
vstatus = self.valve.status
if vstatus[0] // 100 != IDLE // 100:
self.stop_machine(vstatus)
return vstatus
status = self.level.read_status(self)
if status[0] // 100 == IDLE // 100:
return HasStates.read_status(self)
self.stop_machine(status)
return status
def write_mode(self, mode):
if mode == 'DISABLED':
self.stop_machine((DISABLED, ''))
elif mode == 'AUTO':
self.start_machine(self.watching)
return mode
@status_code(BUSY)
def watching(self, state):
if state.init:
self.valve.write_target(0)
delta = state.delta(10)
raw = self.level.value
if raw > self.value:
self.value -= delta / (3600 * self.hold_hours_range[1])
elif raw < self.value:
self.value -= delta / (3600 * self.hold_hours_range[0])
else:
self.value = raw
if self.value < self.fill_level:
return self.precooling
return Retry
@status_code(BUSY)
def precooling(self, state):
if state.init:
state.fillstart = state.now
self.valve.write_target(1)
delta = state.delta(1)
raw = self.level.value
if raw > self.value:
self.value += delta / (60 * self.fill_minutes_range[0])
elif raw < self.value:
self.value -= delta / (60 * self.fill_minutes_range[0])
else:
self.value = raw
if self.value > self.full_level:
return self.watching
if state.now > state.fillstart + self.fill_delay * 60:
return self.filling
return Retry
@status_code(BUSY)
def filling(self, state):
delta = state.delta(1)
raw = self.level.value
if raw > self.value:
self.value += delta / (60 * self.fill_minutes_range[0])
elif raw < self.value:
self.value += delta / (60 * self.fill_minutes_range[1])
else:
self.value = raw
if self.value > self.full_level:
return self.watching
return Retry
def on_cleanup(self, state):
try:
self.valve.write_target(0)
except Exception:
pass
super().on_cleanup()
@Command()
def fill(self):
self.mode = 'AUTO'
self.start_machine(self.precooling, fillstart=time.time())
@Command()
def stop(self):
self.start_machine(self.watching)

View File

@ -0,0 +1,128 @@
# *****************************************************************************
#
# 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:
# M. Zolliker <markus.zolliker@psi.ch>
#
# *****************************************************************************
from frappy.core import Attached, Command, EnumType, FloatRange, \
Drivable, Parameter, BUSY, IDLE, ERROR
class Valve(Drivable):
motor = Attached(Drivable) # refers to motor module
value = Parameter('valve state',
EnumType(closed=0, open=1, undefined=2),
default=2)
status = Parameter() # inherit properties from Drivable
target = Parameter('valve target',
EnumType(closed=0, open=1),
readonly=False)
# TODO: convert to properties after tests
open_pos = Parameter('target position for open state', FloatRange(), readonly=False, default=80)
mid_pos = Parameter('position for changing speed', FloatRange(), readonly=False, default=5)
fast_speed = Parameter('normal speed', FloatRange(), readonly=False, default=40)
slow_speed = Parameter('reduced speed', FloatRange(), readonly=False, default=10)
__motor_target = None
__status = IDLE, ''
__value = 'undefined'
__drivestate = 0 # 2 when driving to intermediate target or on retry, 1 when driving to final target, 0 when idle
def doPoll(self):
mot = self.motor
motpos = mot.read_value()
scode, stext = mot.read_status()
drivestate = self.__drivestate
if scode >= ERROR:
if self.__drivestate and self.__remaining_tries > 0:
drivestate = 2
self.__remaining_tries -= 1
mot.reset()
mot.write_speed(self.slow_speed)
self.__status = BUSY, f'retry {self._action}'
else:
self.__status = ERROR, f'valve motor: {stext}'
elif scode < BUSY:
if self.__motor_target is not None and mot.target != self.__motor_target:
self.__status = ERROR, 'motor was driven directly'
elif drivestate == 2:
self.goto(self.target)
drivestate = 1
else:
if -3 < motpos < 3:
self.__value = 'closed'
self.__status = IDLE, ''
elif self.open_pos * 0.5 < motpos < self.open_pos * 1.5:
self.__value = 'open'
self.__status = IDLE, ''
else:
self.__status = ERROR, 'undefined'
if self.__drivestate and not self.isBusy(self.__status):
drivestate = 0
self.__motor_target = None
self.setFastPoll(False)
self.__drivestate = drivestate
self.read_status()
self.read_value()
def read_status(self):
return self.__status
def read_value(self):
if self.read_status()[0] >= BUSY:
return 'undefined'
return self.__value
def goto(self, target):
"""go to open, closed or intermediate position
the intermediate position is targeted when a speed change is needed
return 2 when a retry is needed, 1 else
"""
mot = self.motor
if target: # 'open'
self._action = 'opening'
if True or mot.value > self.mid_pos:
mot.write_speed(self.fast_speed)
self.__motor_target = mot.write_target(self.open_pos)
return 1
mot.write_speed(self.slow_speed)
self.__motor_target = mot.write_target(self.mid_pos)
return 2
self._action = 'closing'
if mot.value > self.mid_pos * 2:
mot.write_speed(self.fast_speed)
self.__motor_target = mot.write_target(self.mid_pos)
return 2
mot.write_speed(self.slow_speed)
self.__motor_target = mot.write_target(0)
return 1
def write_target(self, target):
self.__remaining_tries = 5
self.__drivestate = self.goto(target)
self.__status = BUSY, self._action
self.read_status()
self.read_value()
self.setFastPoll(True)
@Command() # python decorator to mark it as a command
def stop(self):
"""stop the motor -> value might get undefined"""
self.__drivestate = 0
self.motor.stop()

View File

@ -1,83 +1,105 @@
import os
from glob import glob
from pathlib import Path
from configparser import ConfigParser
from frappy.errors import ConfigError
class Lsc:
def __init__(self, modfactory, ls_uri, ls_ioname='lsio', ls_devname='ls', ls_model='336', **kwds):
self.modfactory = Mod = modfactory
self.model = ls_model
self.ioname = ls_ioname
self.devname = ls_devname
self.io = Mod(self.ioname, cls=f'frappy_psi.lakeshore.IO{self.model}',
description='comm. to lakeshore in cc rack',
uri=ls_uri)
self.dev = Mod(self.devname, cls=f'frappy_psi.lakeshore.Device{self.model}',
description='lakeshore in cc rack', io=self.ioname, curve_handling=True)
self.loops = {}
self.outputs = {}
class Rack:
configbase = Path('/home/l_samenv/.config/frappy_instruments')
def __init__(self, modfactory, **kwds):
self.modfactory = modfactory
instpath = self.configbase / os.environ['Instrument']
sections = {}
self.config = {}
files = glob(str(instpath / '*.ini'))
for filename in files:
parser = ConfigParser()
parser.optionxform = str
parser.read([filename])
for section in parser.sections():
prev = sections.get(section)
if prev:
raise ConfigError(f'duplicate {section} section in {filename} and {prev}')
sections[section] = filename
self.config.update(parser.items(section))
if 'rack' not in sections:
raise ConfigError(f'no rack found in {instpath}')
self.props = {} # dict (<property>, <method>) of value
self.mods = {} # dict (<property>, <method>) of list of <cfg>
def set_props(self, mod, **kwds):
for prop, method in kwds.items():
value = self.props.get((prop, method))
if value is None:
# add mod to the list of cfgs to be fixed
self.mods.setdefault((prop, method), []).append(mod)
else:
# set prop in current module
if not mod.get(prop): # do not override given and not empty property
mod[prop] = value
def fix_props(self, method, **kwds):
for prop, value in kwds.items():
if (prop, method) in self.props:
raise ConfigError(f'duplicate call to {method}()')
self.props[prop, method] = value
# set property in modules to be fixed
for mod in self.mods.get((prop, method), ()):
mod[prop] = value
def lakeshore(self, ls_uri=None, io='ls_io', dev='ls', model='336', **kwds):
Mod = self.modfactory
self.fix_props('lakeshore', io=io, device=dev)
self.ls_model = model
self.ls_dev = dev
ls_uri = ls_uri or self.config.get('ls_uri')
Mod(io, cls=f'frappy_psi.lakeshore.IO{self.ls_model}',
description='comm. to lakeshore in cc rack', uri=ls_uri)
self.dev = Mod(dev, cls=f'frappy_psi.lakeshore.Device{self.ls_model}',
description='lakeshore in cc rack', io=io, curve_handling=True)
def sensor(self, name, channel, calcurve, **kwds):
Mod = self.modfactory
kwds.setdefault('cls', f'frappy_psi.lakeshore.Sensor{self.model}')
kwds.setdefault('cls', f'frappy_psi.lakeshore.Sensor{self.ls_model}')
kwds.setdefault('description', f'T sensor {name}')
return Mod(name, channel=channel, calcurve=calcurve,
io=self.ioname, device=self.devname, **kwds)
def loop(self, name, channel, calcurve, **kwds):
Mod = self.modfactory
kwds.setdefault('cls', f'frappy_psi.lakeshore.Loop{self.model}')
kwds.setdefault('description', f'T loop {name}')
mod = Mod(name, channel=channel, calcurve=calcurve,
io=self.ioname, device=self.devname, **kwds)
self.loops[name] = mod
return mod
device=self.ls_dev, **kwds)
self.set_props(mod, io='lakeshore', dev='lakeshore')
def heater(self, name, max_heater, resistance, output_no=1, **kwds):
def loop(self, name, channel, calcurve, output_module, **kwds):
Mod = self.modfactory
kwds.setdefault('cls', f'frappy_psi.lakeshore.Loop{self.ls_model}')
kwds.setdefault('description', f'T loop {name}')
Mod(name, channel=channel, calcurve=calcurve, output_module=output_module,
device=self.ls_dev, **kwds)
self.fix_props(f'heater({output_module})', description=f'heater for {name}')
def heater(self, name, output_no, max_heater, resistance, **kwds):
Mod = self.modfactory
if output_no == 1:
kwds.setdefault('cls', f'frappy_psi.lakeshore.MainOutput{self.model}')
kwds.setdefault('cls', f'frappy_psi.lakeshore.MainOutput{self.ls_model}')
elif output_no == 2:
kwds.setdefault('cls', f'frappy_psi.lakeshore.SecondaryOutput{self.model}')
kwds.setdefault('cls', f'frappy_psi.lakeshore.SecondaryOutput{self.ls_model}')
else:
return
kwds.setdefault('description', '')
mod = Mod(name, max_heater=max_heater, resistance=resistance,
io=self.ioname, device=self.devname, **kwds)
self.outputs[name] = mod
return mod
mod = Mod(name, max_heater=max_heater, resistance=resistance, **kwds)
self.set_props(mod, io='lakeshore', device='lakeshore', description=f'heater({name})')
def __enter__(self):
return self
def __exit__(self, exc_type, exc_val, exc_tb):
outmodules = dict(self.outputs)
for name, loop in self.loops.items():
outname = loop.get('output_module')
if outname:
out = outmodules.pop(outname, None)
if not out:
raise KeyError(f'{outname} is not a output module in this lakeshore')
else:
if not outmodules:
raise KeyError(f'{name} needs an output module on this lakeshore')
outname = list(outmodules)[0]
out = outmodules.pop(outname)
loop['output_module'] = outname
if not out['description']:
out['description'] = f'heater for {outname}'
class CCU:
def __init__(self, Mod, ccu_uri, ccu_ioname='ccuio', ccu_devname='ccu', he=None, n2=None, **kwds):
self.ioname = ccu_ioname
self.devname = ccu_devname
Mod(self.ioname, 'frappy_psi.ccu4.CCU4IO',
def ccu(self, ccu_uri=None, ccu_io='ccu_io', he=None, n2=None, **kwds):
Mod = self.modfactory
self.ccu_io = ccu_io
ccu_uri = ccu_uri or self.config.get('ccu_uri')
# self.devname = ccu_devname
Mod(ccu_io, 'frappy_psi.ccu4.IO',
'comm. to CCU4', uri=ccu_uri)
if he:
if not isinstance(he, str): # e.g. True
he = 'He_lev'
Mod(he, cls='frappy_psi.ccu4.HeLevel',
description='the He Level', io=self.ioname)
description='the He Level', io=self.ccu_io)
if n2:
if isinstance(n2, str):
n2 = n2.split(',')
@ -86,40 +108,32 @@ class CCU:
n2, valve, upper, lower = n2 + ['N2_lev', 'N2_valve', 'N2_upper', 'N2_lower'][len(n2):]
print(n2, valve, upper, lower)
Mod(n2, cls='frappy_psi.ccu4.N2Level',
description='the N2 Level', io=self.ioname,
description='the N2 Level', io=ccu_io,
valve=valve, upper=upper, lower=lower)
Mod(valve, cls='frappy_psi.ccu4.N2FillValve',
description='LN2 fill valve', io=self.ioname)
description='LN2 fill valve', io=ccu_io)
Mod(upper, cls='frappy_psi.ccu4.N2TempSensor',
description='upper LN2 sensor')
Mod(lower, cls='frappy_psi.ccu4.N2TempSensor',
description='lower LN2 sensor')
class HePump:
def __init__(self, Mod, hepump_uri, hepump_io='hepump_io', hemotname='hepump_mot', **kwds):
Mod(hepump_io, 'frappy_psi.trinamic.BytesIO', 'He pump connection', uri=hepump_uri)
Mod(hemotname, 'frappy_psi.trinamic.Motor', 'He pump valve motor', io=hepump_io)
class Rack:
rackfile = '/home/l_samenv/.config/racks.ini'
def __init__(self, modfactory, **kwds):
self.modfactory = modfactory
parser = ConfigParser()
parser.optionxform = str
parser.read([self.rackfile])
kwds.update(parser.items(os.environ['Instrument']))
self.kwds = kwds
def lakeshore(self):
return Lsc(self.modfactory, **self.kwds)
def ccu(self, **kwds):
kwds.update(self.kwds)
return CCU(self.modfactory, **kwds)
def hepump(self):
return HePump(self.modfactory, **self.kwds)
def hepump(self, hepump_uri=None, hepump_type=None, hepump_io='hepump_io',
hepump='hepump', hepump_mot='hepump_mot', hepump_valve='hepump_valve',
flow_sensor='flow_sensor', pump_pressure='pump_pressure', nv='nv',
ccu_io='ccu_io', **kwds):
Mod = self.modfactory
hepump_type = hepump_type or self.config.get('hepump_type', 'no')
Mod(nv, 'frappy_psi.ccu4.NeedleValveFlow', 'flow from flow sensor or pump pressure',
flow_sensor=flow_sensor, pressure=pump_pressure, io=ccu_io)
Mod(pump_pressure, 'frappy_psi.ccu4.Pressure', 'He pump pressure', io=ccu_io)
if hepump_type == 'no':
print('no pump, no flow meter - using flow from pressure alone')
return
hepump_uri = hepump_uri or self.config['hepump_uri']
Mod(hepump_io, 'frappy.io.BytesIO', 'He pump connection', uri=hepump_uri)
Mod(hepump, 'frappy_psi.hepump.HePump', 'He pump', pump_type=hepump_type,
valvemotor=hepump_mot, valve=hepump_valve, flow=nv)
Mod(hepump_mot, 'frappy_psi.hepump.Motor', 'He pump valve motor', io=hepump_io, maxcurrent=2.8)
Mod(hepump_valve, 'frappy_psi.butterflyvalve.Valve', 'He pump valve', motor=hepump_mot)
Mod(flow_sensor, 'frappy_psi.sensirion.FlowSensor', 'Flow Sensor', io=hepump_io, nsamples=160)

View File

@ -23,20 +23,21 @@
import time
import math
from frappy.lib.enum import Enum
from frappy.lib import clamp
# the most common Frappy classes can be imported from frappy.core
from frappy.core import HasIO, Parameter, Command, Readable, Writable, Drivable, \
Property, StringIO, BUSY, IDLE, WARN, ERROR, DISABLED, Attached
Property, StringIO, BUSY, IDLE, WARN, ERROR, DISABLED, Attached, nopoll
from frappy.datatypes import BoolType, EnumType, FloatRange, StructOf, \
StatusType, IntRange, StringType, TupleOf
from frappy.errors import CommunicationFailedError
from frappy.states import HasStates, status_code, Retry
M = Enum(idle=0, opening=1, closing=2, opened=3, closed=5, no_motor=6)
M = Enum(idle=0, opening=1, closing=2, opened=3, closed=4, no_motor=5)
A = Enum(disabled=0, manual=1, auto=2)
class CCU4IO(StringIO):
class IO(StringIO):
"""communication with CCU4"""
# for completeness: (not needed, as it is the default)
end_of_line = '\n'
@ -44,8 +45,8 @@ class CCU4IO(StringIO):
identification = [('cid', r'cid=CCU4.*')]
class CCU4Base(HasIO):
ioClass = CCU4IO
class Base(HasIO):
ioClass = IO
def command(self, **kwds):
"""send a command and get the response
@ -79,7 +80,7 @@ class CCU4Base(HasIO):
return result
class HeLevel(CCU4Base, Readable):
class HeLevel(Base, Readable):
"""He Level channel of CCU4"""
value = Parameter(unit='%')
@ -121,10 +122,10 @@ class HeLevel(CCU4Base, Readable):
return self.command(hfu=value)
class Valve(CCU4Base, Writable):
class Valve(Base, Writable):
value = Parameter('relay state', BoolType())
target = Parameter('relay target', BoolType())
ioClass = CCU4IO
ioClass = IO
STATE_MAP = {0: (0, (IDLE, 'off')),
1: (1, (IDLE, 'on')),
2: (0, (ERROR, 'no valve')),
@ -173,7 +174,7 @@ class N2TempSensor(Readable):
value = Parameter('LN2 T sensor', FloatRange(unit='K'), default=0)
class N2Level(CCU4Base, Readable):
class N2Level(Base, Readable):
valve = Attached(Writable, mandatory=False)
lower = Attached(Readable, mandatory=False)
upper = Attached(Readable, mandatory=False)
@ -285,138 +286,320 @@ class N2Level(CCU4Base, Readable):
self.command(nc=0)
class FlowPressure(CCU4Base, Readable):
class HasFilter:
__value1 = None
__value = None
__last = None
def filter(self, filter_time, value):
now = time.time()
if self.__value is None:
self.__last = now
self.__value1 = value
self.__value = value
weight = (now - self.__last) / filter_time
self.__value1 += weight * (value - self.__value)
self.__value += weight * (self.__value1 - self.__value)
self.__last = now
return self.__value
class Pressure(HasFilter, Base, Readable):
value = Parameter(unit='mbar')
mbar_offset = Parameter(unit='mbar', default=0.8, readonly=False)
mbar_offset = Parameter('offset in mbar', FloatRange(unit='mbar'), default=0.8, readonly=False)
filter_time = Parameter('filter time', FloatRange(unit='sec'), readonly=False, default=3)
pollinterval = Parameter(default=0.25)
def read_value(self):
return self.filter(self.command(f=float)) - self.mbar_offset
return self.filter(self.filter_time, self.command(f=float)) - self.mbar_offset
class NeedleValve(HasStates, CCU4Base, Drivable):
flow = Attached(Readable, mandatory=False)
flow_pressure = Attached(Readable, mandatory=False)
class NeedleValveFlow(HasStates, Base, Drivable):
flow_sensor = Attached(Readable, mandatory=False)
pressure = Attached(Pressure, mandatory=False)
use_pressure = Parameter('flag (use pressure instead of flow meter)', BoolType(),
readonly=False, default=False)
lnm_per_mbar = Parameter('scale factor', FloatRange(unit='lnm/mbar'), readonly=False, default=0.6)
value = Parameter(unit='ln/min')
target = Parameter(unit='ln/min')
lnm_per_mbar = Parameter(unit='ln/min/mbar', default=0.6, readonly=False)
use_pressure = Parameter('use flow from pressure', BoolType(),
default=False, readonly=False)
motor_state = Parameter('motor_state', EnumType(M))
motor_state = Parameter('motor_state', EnumType(M), default=0)
tolerance = Parameter('tolerance', FloatRange(0), value=0.25, readonly=False)
tolerance2 = Parameter('tolerance limit above 2 lnm', FloatRange(0), value=0.5, readonly=False)
prop = Parameter('proportional term', FloatRange(unit='s/lnm'), readonly=False)
prop = Parameter('proportional term', FloatRange(unit='s/lnm'), readonly=False, default=0.001)
deriv = Parameter('min progress time constant', FloatRange(unit='s'),
default=30, readonly=False)
settle = Parameter('time within tolerance before getting quiet', FloatRange(unit='s'),
default=30, readonly=False)
step_factor = Parameter('factor (no progress time) / (min step size)', FloatRange(), default=300)
control_active = Parameter('control active flag', BoolType(), readonly=False)
pollinterval = Parameter(default=1)
step_factor = Parameter('factor (no progress time) / (min step size)', FloatRange(), default=300, readonly=False)
control_active = Parameter('control active flag', BoolType(), readonly=False, default=1)
min_open_step = Parameter('minimal open step', FloatRange(unit='s'), readonly=False, default=0.06)
min_close_step = Parameter('minimal close step', FloatRange(unit='s'), readonly=False, default=0.05)
raw_open_step = Parameter('step after direction change', FloatRange(unit='s'), readonly=False, default=0.12)
raw_close_step = Parameter('step after direction change', FloatRange(unit='s'), readonly=False, default=0.04)
pollinterval = Parameter(default=5)
_ref_time = 0
_ref_dif = 0
_last_cycle = 0
_last_progress = 0
_dir = 0
_rawdir = 0
_step = 0
def initModule(self):
if self.pressure:
self.pressure.addCallback('value', self.update_from_pressure)
if self.flow_sensor:
self.flow_sensor.addCallback('value', self.update_from_flow)
super().initModule()
if self.flow_pressure:
self.flow_pressure.addCallback('value', self.update_flow_pressure)
if self.flow:
self.flow.addCallback('value', self.update_flow)
self.write_tolerance(self.tolerance)
def update_from_flow(self, value):
if not self.use_pressure:
self.value = value
# self.cycle_machine()
def update_from_pressure(self, value):
if self.use_pressure:
self.value = value * self.lnm_per_mbar
# self.cycle_machine()
# def doPoll(self):
# """only the updates should trigger the machine"""
def read_value(self):
p = self.pressure.read_value() * self.lnm_per_mbar
f = self.flow_sensor.read_value()
# self.log.info('p %g f %g +- %.2g', p, f, self.flow_sensor.stddev)
self.read_motor_state()
return p if self.use_pressure else f
def write_tolerance(self, tolerance):
if hasattr(self.flow_pressure, 'tolerance'):
self.flow_pressure.tolerance = tolerance / self.lnm_per_mbar
if hasattr(self.flow, 'tolerance'):
self.flow.tolerance = tolerance
if hasattr(self.pressure, 'tolerance'):
self.pressure.tolerance = tolerance / self.lnm_per_mbar
if hasattr(self.flow_sensor, 'tolerance'):
self.flow_sensor.tolerance = tolerance
def read_use_pressure(self):
if self.flow_pressure:
if self.flow:
if self.pressure:
if self.flow_sensor:
return self.use_pressure
return True
return False
def update_flow(self, value):
if not self.use_pressure:
self.value = value
self.cycle_machine()
def update_flow_pressure(self, value):
if self.use_pressure:
self.value = value * self.lnm_per_mbar
self.cycle_machine()
def write_target(self, value):
self.start_machine(self.controlling, in_tol_time=0,
ref_time=0, ref_dif=0, prev_dif=0)
self.start_machine(self.change_target, fast_poll=1)
@status_code(BUSY)
def unblock_from_open(self, state):
self.motor_state = self.command(fm=int)
if self.motor_state == 'opened':
self.command(mp=-60)
return Retry
if self.motor_state == 'closing':
return Retry
if self.motor_state == 'closed':
if self.value > max(1, self.target):
return Retry
state.flow_before = self.value
state.wiggle = 1
state.start_wiggle = state.now
self.command(mp=60)
return self.unblock_open
return self.approaching
def change_target(self, state):
state.in_tol_time = 0
state.last_minstep = {}
state.last_progress = state.now
state.ref_time = 0
state.ref_dif = 0
state.prev_dif = 0 # used?
state.last_close_time = 0
state.last_pulse_time = 0
state.raw_fact = 1
state.raw_step = 0
if abs(self.target - self.value) < self._tolerance():
return self.at_target
return self.raw_control
def start_direction(self, state):
if self.target > self.value:
self._dir = 1
state.minstep = self.min_open_step
else:
self._dir = -1
state.minstep = self.min_close_step
state.prev = []
def perform_pulse(self, state):
tol = self._tolerance()
dif = self.target - self.value
difdir = dif * self._dir
state.last_pulse_time = state.now
if difdir > tol:
step = state.minstep + (difdir - tol) * self.prop
elif difdir > 0:
step = state.minstep * difdir / tol
else:
return
self.log.info('MP %g dif=%g tol=%g', step * self._dir, dif, tol)
self.command(mp=clamp(-1, step * self._dir, 1))
@status_code(BUSY)
def unblock_open(self, state):
self.motor_state = self.command(fm=int)
if self.value < state.flow_before:
state.flow_before_open = self.value
elif self.value > state.flow_before + 1:
state.wiggle = -state.wiggle / 2
self.command(mp=state.wiggle)
state.start_wiggle = state.now
return self.unblock_close
if self.motor_state == 'opening':
def raw_control(self, state):
tol = self._tolerance()
if state.init:
self.start_direction(state)
state.raw_step = self.raw_open_step if self._dir > 0 else -self.raw_close_step
state.raw_fact = 1
# if self.read_motor_state() == M.closed:
# # TODO: also check for flow near lower limit ? but only once after change_target
# self.log.info('start with fast opening')
# state.raw_step = 1
# self._dir = 1
difdir = (self.target - self.value) * self._dir
state.prev.append(difdir)
state.diflim = max(0, difdir - tol * 1)
state.success = 0
self.command(mp=state.raw_step)
self.log.info('first rawstep %g', state.raw_step)
state.last_pulse_time = state.now
state.raw_pulse_cnt = 0
state.cycle_cnt = 0
return Retry
if self.motor_state == 'idle':
self.command(mp=state.wiggle)
difdir = (self.target - self.value) * self._dir
state.cycle_cnt += 1
state.prev.append(difdir)
del state.prev[:-5]
if state.prev[-1] > max(state.prev[:-1]):
# TODO: use the amount of overshoot to reduce the raw_step
state.cycle_cnt = 0
self.log.info('difference is increasing %s', ' '.join(f'{v:g}' for v in state.prev))
return Retry
if self.motor_state == 'opened':
if state.now < state.start_wiggle + 20:
return Retry
return self.final_status(ERROR, 'can not open')
if state.cycle_cnt >= 5:
state.cycle_cnt = 0
state.diflim = max(tol, min(state.prev) - tol * 0.5)
state.raw_pulse_cnt += 1
self.command(mp=state.raw_step * state.raw_fact)
self.log.info('rawstep %g', state.raw_step)
if state.raw_pulse_cnt % 5 == 0 and state.raw_pulse_cnt > 5:
state.raw_fact *= 1.25
return Retry
if difdir >= state.diflim:
state.success = max(0, state.success - 1)
return Retry
state.success += 1
if state.success <= 3:
return Retry
if state.raw_pulse_cnt < 3:
state.raw_fact = 1 - (3 - state.raw_pulse_cnt) ** 2 * 0.05
if state.raw_fact != 1:
if self._dir > 0:
self.raw_open_step *= state.raw_fact
self.log.info('raw_open_step %g f=%g', self.raw_open_step, state.raw_fact)
self.min_open_pulse = min(self.min_open_pulse, self.raw_open_step)
else:
self.raw_close_step *= state.raw_fact
self.log.info('raw_close_step %g f=%g', self.raw_close_step, state.raw_fact)
self.min_close_pulse = min(self.min_close_pulse, self.raw_close_step)
return self.controlling
# @status_code(BUSY)
# def raw_control(self, state):
# tol = self._tolerance()
# if state.init:
# self.start_direction(state)
# if self._dir != self._rawdir:
# self._rawdir = self._dir
# state.first_step = self.first_open_step if self._dir > 0 else -self.first_close_step
# else:
# state.first_step = 0
# state.first_fact = 1
# # if self.read_motor_state() == M.closed:
# # # TODO: also check for flow near lower limit ? but only once after change_target
# # self.log.info('start with fast opening')
# # state.first_step = 1
# # self._dir = 1
# difdir = (self.target - self.value) * self._dir
# state.prev = [difdir]
# state.diflim = max(0, difdir - tol * 0.5)
# state.success = 0
# if state.first_step:
# self.command(mp=state.first_step)
# else:
# self.perform_pulse(state)
# self.log.info('firststep %g', state.first_step)
# state.last_pulse_time = state.now
# state.raw_pulse_cnt = 0
# return Retry
# difdir = (self.target - self.value) * self._dir
# if state.delta(5):
# state.diflim = max(0, min(state.prev) - tol * 0.1)
# state.prev = [difdir]
# state.raw_pulse_cnt += 1
# if state.first_step and state.raw_pulse_cnt % 10 == 0:
# self.command(mp=state.first_step * state.first_fact)
# self.log.info('repeat firststep %g', state.first_step * state.first_fact)
# state.first_fact *= 1.25
# else:
# self.perform_pulse(state)
# return Retry
# state.prev.append(difdir)
# if difdir >= state.diflim:
# state.success = max(0, state.success - 1)
# return Retry
# state.success += 1
# if state.success <= 5:
# return Retry
# if state.first_step:
# if state.raw_pulse_cnt < 3:
# state.first_fact = 1 - (3 - state.raw_pulse_cnt) ** 2 * 0.04
# if state.first_fact != 1:
# if self._dir > 0:
# self.first_open_step *= state.first_fact
# self.log.info('first_open_step %g f=%g', self.first_open_step, state.first_fact)
# else:
# self.first_close_step *= state.first_fact
# self.log.info('first_close_step %g f=%g', self.first_close_step, state.first_fact)
# return self.controlling
@status_code(BUSY)
def unblock_close(self, state):
self.motor_state = self.command(fm=int)
if self.value > state.flow_before:
state.flow_before_open = self.value
elif self.value < state.flow_before - 1:
if state.wiggle < self.prop * 2:
return self.final_status(IDLE, '')
state.wiggle = -state.wiggle / 2
self.command(mp=state.wiggle)
state.start_wiggle = state.now
return self.unblock_open
if self.motor_state == 'closing':
def controlling(self, state):
dif = self.target - self.value
if state.init:
self.start_direction(state)
state.ref_dif = abs(dif)
state.ref_time = state.now
state.in_tol_time = 0
difdir = dif * self._dir # negative when overshoot happend
# difdif = dif - state.prev_dif
# state.prev_dif = dif
expected_dif = state.ref_dif * math.exp((state.ref_time - state.now) / self.deriv)
tol = self._tolerance()
if difdir < tol:
# prev_minstep = state.last_minstep.pop(self._dir, None)
# attr = 'min_open_step' if self._dir > 0 else 'min_close_step'
# if prev_minstep is not None:
# # increase minstep
# minstep = getattr(self, attr)
# setattr(self, attr, minstep * 1.1)
# self.log.info('increase %s to %g', attr, minstep)
if difdir > -tol: # within tolerance
delta = state.delta()
state.in_tol_time += delta
if state.in_tol_time > self.settle:
# state.last_minstep.pop(self._dir, None)
self.log.info('at target %g %g', dif, tol)
return self.at_target
if difdir < 0:
return Retry
# self.log.info('minstep=0 dif=%g', dif)
else: # overshoot
self.log.info('overshoot %g', dif)
return self.raw_control
# # overshoot
# prev_minstep = state.last_minstep.pop(self._dir, None)
# if prev_minstep is None:
# minstep = getattr(self, attr) * 0.9
# self.log.info('decrease %s to %g', attr, minstep)
# setattr(self, attr, minstep)
# self.start_step(state, self.target)
# still approaching
if difdir <= expected_dif:
if difdir < expected_dif / 1.25 - tol:
state.ref_time = state.now
state.ref_dif = (difdir + tol) * 1.25
# self.log.info('new ref %g', state.ref_dif)
state.last_progress = state.now
return Retry # progressing: no pulse needed
if state.now < state.last_pulse_time + 2.5:
return Retry
if self.motor_state == 'idle':
self.command(mp=state.wiggle)
return Retry
if self.motor_state == 'closed':
if state.now < state.start_wiggle + 20:
return Retry
return self.final_status(ERROR, 'can not close')
return self.final_status(WARN, 'unblock interrupted')
# TODO: check motor state for closed / opened ?
self.perform_pulse(state)
return Retry
def _tolerance(self):
return min(self.tolerance * min(1, self.value / 2), self.tolerance2)
@ -426,48 +609,67 @@ class NeedleValve(HasStates, CCU4Base, Drivable):
dif = self.target - self.value
if abs(dif) > self._tolerance():
state.in_tol_time = 0
self.log.info('unstable %g', dif)
return self.unstable
return Retry
@status_code(IDLE, 'unstable')
def unstable(self, state):
difdir = (self.target - self.value) * self._dir
if difdir < 0 or self._dir == 0:
return self.raw_control
return self.controlling(state)
@status_code(BUSY)
def controlling(self, state):
delta = state.delta(0)
dif = self.target - self.value
difdif = dif - state.prev_dif
state.prev_dif = dif
self.motor_state = self.command(fm=int)
if self.motor_state == 'closed':
if dif < 0 or difdif < 0:
return Retry
return self.unblock_from_open
elif self.motor_state == 'opened': # trigger also when flow too high?
if dif > 0 or difdif > 0:
return Retry
self.command(mp=-60)
return self.unblock_from_open
def read_motor_state(self):
return self.command(fm=int)
tolerance = self._tolerance()
if abs(dif) < tolerance:
state.in_tol_time += delta
if state.in_tol_time > self.settle:
return self.at_target
@Command
def close(self):
"""close valve fully"""
self.command(mp=-60)
self.motor_state = self.command(fm=int)
self.start_machine(self.closing)
@status_code(BUSY)
def closing(self, state):
if state.init:
state.start_time = state.now
self.read_motor_state()
if self.motor_state == M.closing:
return Retry
expected_dif = state.ref_dif * math.exp((state.now - state.ref_time) / self.deriv)
if abs(dif) < expected_dif:
if abs(dif) < expected_dif / 1.25:
state.ref_time = state.now
state.ref_dif = abs(dif) * 1.25
state.last_progress = state.now
return Retry # progress is fast enough
state.ref_time = state.now
state.ref_dif = abs(dif)
state.step += dif * delta * self.prop
if abs(state.step) < (state.now - state.last_progress) / self.step_factor:
# wait until step size is big enough
if self.motor_state == M.closed:
return self.final_status(IDLE, 'closed')
if state.now < state.start_time + 1:
return Retry
self.command(mp=state.step)
return Retry
return self.final_status(IDLE, 'fixed')
@Command
def open(self):
"""open valve fully"""
self.command(mp=60)
self.read_motor_state()
self.start_machine(self.opening)
@status_code(BUSY)
def opening(self, state):
if state.init:
state.start_time = state.now
self.read_motor_state()
if self.motor_state == M.opening:
return Retry
if self.motor_state == M.opened:
return self.final_status(IDLE, 'opened')
if state.now < state.start_time + 1:
return Retry
return self.final_status(IDLE, 'fixed')
@Command(FloatRange())
def pulse(self, value):
"""perform a motor pulse"""
self.log.info('pulse %g', value)
self.command(mp=value)
if value > 0:
self.motor_state = M.opening
return self.opening
self.motor_state = M.closing
return self.closing

71
frappy_psi/hepump.py Normal file
View File

@ -0,0 +1,71 @@
# *****************************************************************************
#
# 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 BoolType, FloatRange, Parameter, Readable, Writable, Attached, EnumType, nopoll
from frappy_psi.trinamic import Motor
from frappy_psi.ccu4 import Pressure, NeedleValveFlow
class ValveMotor(Motor):
has_inputs = True
class HePump(Writable):
valvemotor = Attached(Motor)
flow = Attached(NeedleValveFlow)
valve = Attached(Writable)
value = Parameter(datatype=BoolType())
target = Parameter(datatype=BoolType())
pump_type = Parameter('pump type', EnumType(no=0, neodry=1, xds35=2, sv65=3), readonly=False, default=0)
eco_mode = Parameter('eco mode', BoolType(), readonly=False)
has_feedback = Parameter('feedback works', BoolType(), readonly=False, default=True)
FLOW_SCALE = {'no': 0, 'neodry': 0.55, 'xds35': 0.6, 'sv65': 0.9}
def write_target(self, value):
self.valvemotor.write_output0(value)
def read_target(self):
return self.valvemotor.read_output0()
def read_value(self):
if self.has_feedback:
return not self.valvemotor.read_input3()
return self.target
def write_pump_type(self, value):
self.flow.pressure_scale = self.FLOW_SCALE[value.name]
def read_eco_mode(self):
if self.pump_type == 'xds35':
return self.valvemotor.read_output1()
return False
def write_eco_mode(self, value):
if self.pump_type == 'xds35':
return self.valvemotor.write_output1(value)
# else silently ignore

View File

@ -39,6 +39,13 @@ from frappy.extparams import StructParam
from frappy_psi.calcurve import CalCurve
def string_to_num(string):
try:
return int(string)
except ValueError:
return float(string)
class IO(StringIO):
"""IO classes of most LakeShore models will inherit from this"""
end_of_line = '\n'
@ -97,8 +104,9 @@ class HasLscIO(HasIO):
if not args:
self.communicate(f'{msghead};*OPC?')
return None
converters = [type(a) for a in args]
values = [a if issubclass(c, str) else f'{a:g}'
# when an argument is given as integer, it might be that this argument might be a float
converters = [string_to_num if isinstance(a, int) else type(a) for a in args]
values = [a if isinstance(a, str) else f'{a:g}'
for c, a in zip(converters, args)]
if ' ' in msghead:
query = msghead.replace(' ', '? ', 1)
@ -839,7 +847,7 @@ class MainOutput(Output):
}
_htr_range = 1
heater_ranges = {5 - i: 10 ** - i for i in range(5)}
heater_ranges = {5 - i: 10 ** -i for i in range(5)}
sorted_factors = sorted((v, i) for i, v in heater_ranges.items())
def read_status(self):
@ -847,6 +855,9 @@ class MainOutput(Output):
return self.HTRST_MAP[st]
def configure(self):
if self._desired_max_power is None:
self.log.info(f'max_heater {self.writeDict} {self.max_heater}')
self.write_max_heater(self.max_heater)
self._htr_range = irng = self.get_best_power_idx(self._desired_max_power)
user_current = max(0.1, min(self.imax, 2 * math.sqrt(self._desired_max_power /
self.heater_ranges[irng] / self.resistance)))
@ -1180,7 +1191,7 @@ class MainOutput336(MainOutput):
imax = 2
vmax = 50
# 3 ranges only
heater_ranges = {i: 10 ** (3 - i) for i in range(5)}
heater_ranges = {3 - i: 10 ** -i for i in range(3)}
sorted_factors = sorted((v, i) for i, v in heater_ranges.items())

96
frappy_psi/sensirion.py Normal file
View File

@ -0,0 +1,96 @@
# *****************************************************************************
#
# 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>
#
# *****************************************************************************
"""sensirion flow sensor,
onnected via an Arduio Nano on a serial connection
shared with the trinamic hepump valve motor
"""
import math
from frappy.core import Parameter, Readable, IntRange, FloatRange, BoolType, BytesIO, HasIO
from frappy.errors import ProgrammingError
class FlowSensor(HasIO, Readable):
value = Parameter(unit='ln/min')
stddev = Parameter('std dev.', FloatRange(unit='ln/min'))
nsamples = Parameter('number of samples for averaging', IntRange(1,1024), default=160)
offset = Parameter('offset correction', FloatRange(unit='ln/min'), readonly=False, default=0)
scale = Parameter('scale factor', FloatRange(), readonly=False, default=2.3)
saved = Parameter('is the current value saved?', BoolType(), readonly=False)
pollinterval = Parameter(default=0.2)
ioClass = BytesIO
_saved = None
def command(self, cmd, nvalues=1):
if len(cmd) == 1: # its a query
command = f'{cmd}\n'
else:
if len(cmd) > 7:
raise ProgrammingError('number does not fit into 6 characters')
command = f'{cmd[0]}{cmd[1:].ljust(6)}\n'
reply = self.io.communicate(command.encode('ascii'), max(1, nvalues * 9))
if nvalues == 1:
return float(reply)
if nvalues:
return tuple(float(s) for s in reply.split())
return None
def doPoll(self):
flow, stddev = self.command('?', nvalues=2)
stddev = stddev / math.sqrt(self.nsamples)
if (flow, stddev) != (self.value, self.stddev):
self.value, self.stddev = flow, stddev
# TODO: treat status (e.g. when reading 0 always)
def read_value(self):
self.doPoll()
return self.value
def read_nsamples(self):
return self.command('n')
def write_nsamples(self, nsamples):
return self.command(f'n{nsamples}')
def read_offset(self):
return self.command('o')
def write_offset(self, offset):
return self.command(f'o{offset:.2f}')
def read_scale(self):
return self.command('g')
def write_scale(self, scale):
return self.command(f'g{scale:.4f}')
def read_saved(self):
if self._saved is None:
self._saved = self.read_scale(), self.read_offset()
return True
return self._saved == (self.scale, self.offset)
def write_saved(self, target):
if target:
self.command('s', nvalues=0)

View File

@ -26,7 +26,8 @@ import struct
from frappy.core import BoolType, Command, EnumType, FloatRange, IntRange, \
HasIO, Parameter, Property, Drivable, PersistentMixin, PersistentParam, Done, \
IDLE, BUSY, ERROR, Limit
IDLE, BUSY, ERROR, Limit, nopoll, ArrayOf
from frappy.properties import HasProperties
from frappy.io import BytesIO
from frappy.errors import CommunicationFailedError, HardwareError, RangeError, IsBusyError
from frappy.rwhandler import ReadHandler, WriteHandler
@ -119,9 +120,6 @@ class Motor(PersistentMixin, HasIO, Drivable):
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(), group='more')
has_home = Parameter('enable home and activate pullup resistor', BoolType(),
default=True, group='more')
auto_reset = Parameter('automatic reset after failure', BoolType(), group='more', readonly=False, default=False)
free_wheeling = writable('', FloatRange(0, 60., unit='sec', fmtstr='%.2f'),
value=0.1, group='motorparam')
@ -132,6 +130,20 @@ class Motor(PersistentMixin, HasIO, Drivable):
readonly=False, default=0, visibility=3, group='more')
max_retry = Parameter('maximum number of retries', IntRange(0, 99), readonly=False, default=0)
stall_thr = Parameter('stallGuard threshold', IntRange(-64, 63), readonly=False, value=0)
input_bits = Parameter('input bits', IntRange(0, 255), group='more', export=False)
input1 = Parameter('input 1', BoolType(), export=False, group='more')
input2 = Parameter('input 2', BoolType(), export=False, group='more')
input3 = Parameter('input 3', BoolType(), export=False, group='more')
output0 = Parameter('output 0', BoolType(), readonly=False, export=False, group='more', default=0)
output1 = Parameter('output 1', BoolType(), readonly=False, export=False, group='more', default=0)
home = Parameter('state of home switch (input 3)', BoolType(), group='more', export=False)
has_home = Property('enable home and activate pullup resistor', BoolType(), export=False,
default=True)
has_inputs = Property('inputs are polled', BoolType(), export=False,
default=False)
with_pullup = Property('activate pullup', BoolType(), export=False,
default=True)
pollinterval = Parameter(group='more')
target_min = Limit()
target_max = Limit()
@ -145,6 +157,18 @@ class Motor(PersistentMixin, HasIO, Drivable):
_loading = False # True when loading parameters
_drv_try = 0
def checkProperties(self):
super().checkProperties()
if self.has_home:
self.parameters['home'].export = '_home'
self.setProperty('has_inputs', True)
if not self.has_inputs:
self.setProperty('with_pullup', False)
def writeInitParams(self):
super().writeInitParams()
self.comm(SET_IO, 0, self.with_pullup)
def comm(self, cmd, adr, value=0, bank=0):
"""set or get a parameter
@ -402,13 +426,6 @@ class Motor(PersistentMixin, HasIO, Drivable):
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"""
@ -459,3 +476,47 @@ class Motor(PersistentMixin, HasIO, Drivable):
def set_axis_par(self, adr, value):
"""set arbitrary motor parameter"""
return self.comm(SET_AXIS_PAR, adr, value)
def read_input_bits(self):
if not self.has_inputs:
return 0
bits = self.comm(GET_IO, 255)
self.input1 = bool(bits & 2)
self.input2 = bool(bits & 4)
self.input3 = bool(bits & 8)
self.home = not self.input3
return bits
@nopoll
def read_home(self):
self.read_input_bits()
return self.home
@nopoll
def read_input1(self):
self.read_input_bits()
return self.input1
@nopoll
def read_input2(self):
self.read_input_bits()
return self.input2
@nopoll
def read_input3(self):
self.read_input_bits()
return self.input3
def write_output0(self, value):
return self.comm(SET_IO, 0, value, bank=2)
@nopoll
def read_output0(self):
return self.comm(GET_IO, 0, bank=2)
def write_output1(self, value):
return self.comm(SET_IO, 1, value, bank=2)
@nopoll
def read_output1(self):
return self.comm(GET_IO, 1, bank=2)