export from internal gitlab

This commit is contained in:
wakonig_k 2022-07-07 19:36:33 +02:00
parent b1a3cd3919
commit 52ce30dc9a
32 changed files with 5119 additions and 0 deletions

8
.gitignore vendored Normal file
View File

@ -0,0 +1,8 @@
**/venv
**/.idea
*.log
**/__pycache__
.DS_Store
**/out
**/.vscode
**/.pytest_cache

15
.gitlab-ci.yml Normal file
View File

@ -0,0 +1,15 @@
# This file is a template, and might need editing before it works on your project.
# Official language image. Look for the different tagged releases at:
# https://hub.docker.com/r/library/python/tags/
image: "python:3.9"
#commands to run in the Docker container before starting each job.
before_script:
- pip install -r ./requirements.txt
- pip install -e .
# different stages in the pipeline
stages:
- Test
pytest:
stage: Test
script:
- pytest -v ./tests

View File

@ -0,0 +1,6 @@
from .galil.galil_ophyd import GalilMotor
from .npoint.npoint import NPointAxis
from .smaract.smaract_ophyd import SmaractMotor
from .sim.sim import SynAxisMonitor, SynAxisOPAAS
from .sls_devices.sls_devices import SLSOperatorMessages
from .rt_lamni import RtLamniMotor

View File

@ -0,0 +1 @@
from .galil_ophyd import GalilMotor, GalilController

View File

@ -0,0 +1,533 @@
import functools
import logging
import threading
import time
from typing import List
import numpy as np
from ophyd import Component as Cpt
from ophyd import Device, PositionerBase
from ophyd.status import wait as status_wait
from ophyd.utils import ReadOnlyError
from ophyd_devices.utils.controller import Controller, threadlocked
from ophyd_devices.utils.socket import SocketIO, SocketSignal, raise_if_disconnected
from prettytable import PrettyTable
logger = logging.getLogger("galil")
class GalilCommunicationError(Exception):
pass
class GalilError(Exception):
pass
class BECConfigError(Exception):
pass
def retry_once(fcn):
"""Decorator to rerun a function in case a SmaractCommunicationError was raised. This may happen if the buffer was not empty."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
try:
val = fcn(self, *args, **kwargs)
except (GalilCommunicationError, GalilError):
val = fcn(self, *args, **kwargs)
return val
return wrapper
class GalilController(Controller):
USER_ACCESS = [
"describe",
"show_running_threads",
"galil_show_all",
"socket_put_and_receive",
"socket_put_confirmed",
]
def __init__(
self,
*,
name="GalilController",
kind=None,
parent=None,
socket=None,
attr_name="",
labels=None,
):
if not hasattr(self, "_initialized") or not self._initialized:
self._galil_axis_per_controller = 8
self._axis = [None for axis_num in range(self._galil_axis_per_controller)]
super().__init__(
name=name,
socket=socket,
attr_name=attr_name,
parent=parent,
labels=labels,
kind=kind,
)
def on(self, controller_num=0) -> None:
"""Open a new socket connection to the controller"""
if not self.connected:
self.sock.open()
self.connected = True
else:
logger.info("The connection has already been established.")
# warnings.warn(f"The connection has already been established.", stacklevel=2)
def off(self) -> None:
"""Close the socket connection to the controller"""
if self.connected:
self.sock.close()
self.connected = False
else:
logger.info("The connection is already closed.")
def set_axis(self, axis: Device, axis_nr: int) -> None:
"""Assign an axis to a device instance.
Args:
axis (Device): Device instance (e.g. GalilMotor)
axis_nr (int): Controller axis number
"""
self._axis[axis_nr] = axis
def socket_put(self, val: str) -> None:
self.sock.put(f"{val}\r".encode())
def socket_get(self) -> str:
return self.sock.receive().decode()
@retry_once
@threadlocked
def socket_put_and_receive(self, val: str, remove_trailing_chars=True) -> str:
self.socket_put(val)
if remove_trailing_chars:
return self._remove_trailing_characters(self.sock.receive().decode())
return self.socket_get()
@retry_once
def socket_put_confirmed(self, val: str) -> None:
"""Send message to controller and ensure that it is received by checking that the socket receives a colon.
Args:
val (str): Message that should be sent to the socket
Raises:
GalilCommunicationError: Raised if the return value is not a colon.
"""
return_val = self.socket_put_and_receive(val)
if return_val != ":":
raise GalilCommunicationError(
f"Expected return value of ':' but instead received {return_val}"
)
def is_axis_moving(self, axis_Id) -> bool:
return bool(float(self.socket_put_and_receive(f"MG _BG{axis_Id}")))
def is_thread_active(self, thread_id: int) -> bool:
val = float(self.socket_put_and_receive(f"MG_XQ{thread_id}"))
if val == -1:
return False
return True
def _remove_trailing_characters(self, var) -> str:
if len(var) > 1:
return var.split("\r\n")[0]
return var
def stop_all_axes(self) -> str:
return self.socket_put_and_receive(f"XQ#STOP,1")
def axis_is_referenced(self, axis_Id_numeric) -> bool:
return bool(float(self.socket_put_and_receive(f"MG axisref[{axis_Id_numeric}]").strip()))
def show_running_threads(self) -> None:
t = PrettyTable()
t.title = f"Threads on {self.sock.host}:{self.sock.port}"
t.field_names = [str(ax) for ax in range(self._galil_axis_per_controller)]
t.add_row(
[
"active" if self.is_thread_active(t) else "inactive"
for t in range(self._galil_axis_per_controller)
]
)
print(t)
def is_motor_on(self, axis_Id) -> bool:
return not bool(float(self.socket_put_and_receive(f"MG _MO{axis_Id}").strip()))
def get_motor_limit_switch(self, axis_Id) -> list:
ret = self.socket_put_and_receive(f"MG _LF{axis_Id}, _LR{axis_Id}")
high, low = ret.strip().split(" ")
return [not bool(float(low)), not bool(float(high))]
def describe(self) -> None:
t = PrettyTable()
t.title = f"{self.__class__.__name__} on {self.sock.host}:{self.sock.port}"
t.field_names = [
"Axis",
"Name",
"Connected",
"Referenced",
"Motor On",
"Limits",
"Position",
]
for ax in range(self._galil_axis_per_controller):
axis = self._axis[ax]
if axis is not None:
t.add_row(
[
f"{axis.axis_Id_numeric}/{axis.axis_Id}",
axis.name,
axis.connected,
self.axis_is_referenced(axis.axis_Id_numeric),
self.is_motor_on(axis.axis_Id),
self.get_motor_limit_switch(axis.axis_Id),
axis.readback.read().get(axis.name).get("value"),
]
)
else:
t.add_row([None for t in t.field_names])
print(t)
self.show_running_threads()
def galil_show_all(self) -> None:
for controller in self._controller_instances.values():
if isinstance(controller, GalilController):
controller.describe()
class GalilSignalBase(SocketSignal):
def __init__(self, signal_name, **kwargs):
self.signal_name = signal_name
super().__init__(**kwargs)
self.controller = self.parent.controller
self.sock = self.parent.controller.sock
class GalilSignalRO(GalilSignalBase):
def __init__(self, signal_name, **kwargs):
super().__init__(signal_name, **kwargs)
self._metadata["write_access"] = False
def _socket_set(self, val):
raise ReadOnlyError("Read-only signals cannot be set")
class GalilReadbackSignal(GalilSignalRO):
@retry_once
def _socket_get(self) -> float:
"""Get command for the readback signal
Returns:
float: Readback value after adjusting for sign and motor resolution.
"""
current_pos = float(self.controller.socket_put_and_receive(f"TD{self.parent.axis_Id}"))
current_pos *= self.parent.sign
step_mm = self.parent.motor_resolution.get()
return current_pos / step_mm
def read(self):
val = super().read()
if self.parent.axis_Id_numeric == 2:
try:
self.parent.device_manager.devices[
self.parent.rt
].obj.controller.set_rotation_angle(val[self.parent.name]["value"])
except KeyError:
logger.warning("Failed to set RT value during readback.")
return val
class GalilSetpointSignal(GalilSignalBase):
setpoint = 0
def _socket_get(self) -> float:
"""Get command for receiving the setpoint / target value.
The value is not pulled from the controller but instead just the last setpoint used.
Returns:
float: setpoint / target value
"""
return self.setpoint
@retry_once
def _socket_set(self, val: float) -> None:
"""Set a new target value / setpoint value. Before submission, the target value is adjusted for the axis' sign.
Furthermore, it is ensured that all axes are referenced before a new setpoint is submitted.
Args:
val (float): Target value / setpoint value
Raises:
GalilError: Raised if not all axes are referenced.
"""
target_val = val * self.parent.sign
self.setpoint = target_val
axes_referenced = float(self.controller.socket_put_and_receive("MG allaxref"))
if axes_referenced:
while self.controller.is_thread_active(0):
time.sleep(0.1)
self.controller.socket_put_confirmed(f"naxis={self.parent.axis_Id_numeric}")
self.controller.socket_put_confirmed(f"ntarget={target_val:.3f}")
self.controller.socket_put_confirmed("movereq=1")
self.controller.socket_put_confirmed("XQ#NEWPAR")
else:
raise GalilError("Not all axes are referenced.")
class GalilMotorResolution(GalilSignalRO):
@retry_once
def _socket_get(self):
return float(
self.controller.socket_put_and_receive(f"MG stppermm[{self.parent.axis_Id_numeric}]")
)
class GalilMotorIsMoving(GalilSignalRO):
def _socket_get(self):
return (
self.controller.is_axis_moving(self.parent.axis_Id)
or self.controller.is_thread_active(0)
or self.controller.is_thread_active(2)
)
def get(self):
val = super().get()
if val is not None:
self._run_subs(
sub_type=self.SUB_VALUE,
value=val,
timestamp=time.time(),
)
return val
class GalilAxesReferenced(GalilSignalRO):
def _socket_get(self):
return self.controller.socket_put_and_receive("MG allaxref")
class GalilMotor(Device, PositionerBase):
USER_ACCESS = ["controller"]
readback = Cpt(
GalilReadbackSignal,
signal_name="readback",
kind="hinted",
)
user_setpoint = Cpt(GalilSetpointSignal, signal_name="setpoint")
motor_resolution = Cpt(GalilMotorResolution, signal_name="resolution", kind="config")
motor_is_moving = Cpt(GalilMotorIsMoving, signal_name="motor_is_moving", kind="normal")
all_axes_referenced = Cpt(GalilAxesReferenced, signal_name="all_axes_referenced", kind="config")
SUB_READBACK = "readback"
SUB_CONNECTION_CHANGE = "connection_change"
_default_sub = SUB_READBACK
def __init__(
self,
axis_Id,
prefix="",
*,
name,
kind=None,
read_attrs=None,
configuration_attrs=None,
parent=None,
host="mpc2680.psi.ch",
port=8081,
sign=1,
socket_cls=SocketIO,
device_manager=None,
**kwargs,
):
self.axis_Id = axis_Id
self.sign = sign
self.controller = GalilController(socket=socket_cls(host=host, port=port))
self.controller.set_axis(axis=self, axis_nr=self.axis_Id_numeric)
self.tolerance = kwargs.pop("tolerance", 0.5)
self.device_access = kwargs.pop("device_access", {})
self.device_manager = device_manager
if len(self.device_access) > 0 and self.device_manager is None:
raise BECConfigError(
"device_access has been specified but the device_manager cannot be accessed."
)
self.rt = self.device_access.get("rt")
super().__init__(
prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
**kwargs,
)
self.readback.name = self.name
self.controller.subscribe(
self._update_connection_state, event_type=self.SUB_CONNECTION_CHANGE
)
self._update_connection_state()
# self.readback.subscribe(self._forward_readback, event_type=self.readback.SUB_VALUE)
def _update_connection_state(self, **kwargs):
for walk in self.walk_signals():
walk.item._metadata["connected"] = self.controller.connected
def _forward_readback(self, **kwargs):
kwargs.pop("sub_type")
self._run_subs(sub_type="readback", **kwargs)
@raise_if_disconnected
def move(self, position, wait=True, **kwargs):
"""Move to a specified position, optionally waiting for motion to
complete.
Parameters
----------
position
Position to move to
moved_cb : callable
Call this callback when movement has finished. This callback must
accept one keyword argument: 'obj' which will be set to this
positioner instance.
timeout : float, optional
Maximum time to wait for the motion. If None, the default timeout
for this positioner is used.
Returns
-------
status : MoveStatus
Raises
------
TimeoutError
When motion takes longer than `timeout`
ValueError
On invalid positions
RuntimeError
If motion fails other than timing out
"""
self._started_moving = False
timeout = kwargs.pop("timeout", 4)
status = super().move(position, timeout=timeout, **kwargs)
self.user_setpoint.put(position, wait=False)
def move_and_finish():
while self.motor_is_moving.get():
logger.info("motor is moving")
val = self.readback.read()
self._run_subs(
sub_type=self.SUB_READBACK,
value=val,
timestamp=time.time(),
)
time.sleep(0.1)
val = self.readback.read()
success = np.isclose(
val[self.name]["value"],
position,
atol=self.tolerance,
)
self._done_moving(success=success)
logger.info("Move finished")
threading.Thread(target=move_and_finish, daemon=True).start()
try:
if wait:
status_wait(status)
except KeyboardInterrupt:
self.stop()
raise
return status
@property
def axis_Id(self):
return self._axis_Id_alpha
@axis_Id.setter
def axis_Id(self, val):
if isinstance(val, str):
if len(val) != 1:
raise ValueError(f"Only single-character axis_Ids are supported.")
self._axis_Id_alpha = val
self._axis_Id_numeric = ord(val.lower()) - 97
else:
raise TypeError(f"Expected value of type str but received {type(val)}")
@property
def axis_Id_numeric(self):
return self._axis_Id_numeric
@axis_Id_numeric.setter
def axis_Id_numeric(self, val):
if isinstance(val, int):
if val > 26:
raise ValueError(f"Numeric value exceeds supported range.")
self._axis_Id_alpha = val
self._axis_Id_numeric = (chr(val + 97)).capitalize()
else:
raise TypeError(f"Expected value of type int but received {type(val)}")
@property
def egu(self):
"""The engineering units (EGU) for positions"""
return "mm"
def stage(self) -> List[object]:
self.controller.on()
return super().stage()
def unstage(self) -> List[object]:
self.controller.off()
return super().unstage()
def stop(self, *, success=False):
self.controller.stop_all_axes()
return super().stop(success=success)
if __name__ == "__main__":
logging.basicConfig(level=logging.DEBUG)
mock = False
if not mock:
leyey = GalilMotor("H", name="leyey", host="mpc2680.psi.ch", port=8081, sign=-1)
leyey.stage()
status = leyey.move(0, wait=True)
status = leyey.move(10, wait=True)
leyey.read()
leyey.get()
leyey.describe()
leyey.unstage()
else:
from ophyd_devices.utils.socket import SocketMock
leyex = GalilMotor(
"G", name="leyex", host="mpc2680.psi.ch", port=8081, socket_cls=SocketMock
)
leyey = GalilMotor(
"H", name="leyey", host="mpc2680.psi.ch", port=8081, socket_cls=SocketMock
)
leyex.stage()
# leyey.stage()
leyex.controller.galil_show_all()

View File

@ -0,0 +1,491 @@
import logging
import threading
import time
from typing import List
from ophyd import Component as Cpt
from ophyd import Device, PositionerBase, Signal
from ophyd.status import wait as status_wait
from ophyd.utils import ReadOnlyError
from ophyd_devices.utils.controller import Controller
from ophyd_devices.utils.socket import SocketIO, SocketSignal, raise_if_disconnected
from prettytable import PrettyTable
logger = logging.getLogger("galil")
class GalilCommunicationError(Exception):
pass
class GalilError(Exception):
pass
class GalilController(Controller):
def __init__(
self,
*,
name="GalilController",
kind=None,
parent=None,
socket=None,
attr_name="",
labels=None,
):
if not hasattr(self, "_initialized") or not self._initialized:
self._galil_axis_per_controller = 8
self._axis = [None for axis_num in range(self._galil_axis_per_controller)]
super().__init__(
name=name,
socket=socket,
attr_name=attr_name,
parent=parent,
labels=labels,
kind=kind,
)
def on(self, controller_num=0) -> None:
"""Open a new socket connection to the controller"""
if not self.connected:
self.sock.open()
self.connected = True
else:
logger.info("The connection has already been established.")
# warnings.warn(f"The connection has already been established.", stacklevel=2)
def off(self) -> None:
"""Close the socket connection to the controller"""
if self.connected:
self.sock.close()
self.connected = False
else:
logger.info("The connection is already closed.")
def set_axis(self, axis: Device, axis_nr: int) -> None:
"""Assign an axis to a device instance.
Args:
axis (Device): Device instance (e.g. GalilMotor)
axis_nr (int): Controller axis number
"""
self._axis[axis_nr] = axis
def socket_put(self, val: str) -> None:
self.sock.put(f"{val}\r".encode())
def socket_get(self) -> str:
return self.sock.receive().decode()
def socket_put_and_receive(self, val: str, remove_trailing_chars=True) -> str:
self.socket_put(val)
if remove_trailing_chars:
return self._remove_trailing_characters(self.sock.receive().decode())
return self.socket_get()
def socket_put_confirmed(self, val: str) -> None:
"""Send message to controller and ensure that it is received by checking that the socket receives a colon.
Args:
val (str): Message that should be sent to the socket
Raises:
GalilCommunicationError: Raised if the return value is not a colon.
"""
return_val = self.socket_put_and_receive(val)
if return_val != ":":
raise GalilCommunicationError(
f"Expected return value of ':' but instead received {return_val}"
)
def is_axis_moving(self, axis_Id) -> bool:
return bool(float(self.socket_put_and_receive(f"MG _BG{axis_Id}")))
def is_thread_active(self, thread_id: int) -> bool:
val = float(self.socket_put_and_receive(f"MG_XQ{thread_id}"))
if val == -1:
return False
return True
def _remove_trailing_characters(self, var) -> str:
if len(var) > 1:
return var.split("\r\n")[0]
return var
def stop_all_axes(self) -> str:
return self.socket_put_and_receive(f"XQ#STOP,1")
def show_running_threads(self) -> None:
t = PrettyTable()
t.title = f"Threads on {self.sock.host}:{self.sock.port}"
t.field_names = [str(ax) for ax in range(self._galil_axis_per_controller)]
t.add_row(
[
"active" if self.is_thread_active(t) else "inactive"
for t in range(self._galil_axis_per_controller)
]
)
print(t)
def describe(self) -> None:
t = PrettyTable()
t.title = f"{self.__class__.__name__} on {self.sock.host}:{self.sock.port}"
t.field_names = [
"Axis",
"Name",
"Connected",
"Referenced",
"Motor",
"Limits",
"Position",
]
for ax in range(self._galil_axis_per_controller):
axis = self._axis[ax]
if axis is not None:
t.add_row(
[
f"{axis.axis_Id_numeric}/{axis.axis_Id}",
axis.name,
axis.connected,
"NA",
"off",
"",
axis.user_readback.read().get("value"),
]
)
else:
t.add_row([None for t in t.field_names])
print(t)
self.show_running_threads()
def galil_show_all(self) -> None:
for controller in self._controller_instances.values():
controller.describe()
class GalilSignalBase(SocketSignal):
def __init__(self, signal_name, **kwargs):
self.signal_name = signal_name
super().__init__(**kwargs)
self.controller = self.parent.controller
self.sock = self.parent.controller.sock
class GalilSignalRO(GalilSignalBase):
def __init__(self, signal_name, **kwargs):
super().__init__(signal_name, **kwargs)
self._metadata["write_access"] = False
def _socket_set(self, val):
raise ReadOnlyError("Read-only signals cannot be set")
class GalilReadbackSignal(GalilSignalRO):
def _socket_get(self) -> float:
"""Get command for the readback signal
Returns:
float: Readback value after adjusting for sign and motor resolution.
"""
current_pos = float(self.controller.socket_put_and_receive(f"TD{self.parent.axis_Id}\n"))
current_pos *= self.parent.sign
step_mm = self.parent.motor_resolution.get()
return current_pos / step_mm
class GalilSetpointSignal(GalilSignalBase):
setpoint = 0
def _socket_get(self) -> float:
"""Get command for receiving the setpoint / target value.
The value is not pulled from the controller but instead just the last setpoint used.
Returns:
float: setpoint / target value
"""
return self.setpoint
def _socket_set(self, val: float) -> None:
"""Set a new target value / setpoint value. Before submission, the target value is adjusted for the axis' sign.
Furthermore, it is ensured that all axes are referenced before a new setpoint is submitted.
Args:
val (float): Target value / setpoint value
Raises:
GalilError: Raised if not all axes are referenced.
"""
target_val = val * self.parent.sign
self.setpoint = target_val
axes_referenced = float(self.controller.socket_put_and_receive("MG allaxref"))
if axes_referenced:
self.controller.socket_put_confirmed(f"naxis={self.parent.axis_Id_numeric}")
self.controller.socket_put_confirmed(f"ntarget={target_val:.3f}")
self.controller.socket_put_confirmed("movereq=1")
self.controller.socket_put_confirmed("XQ#NEWPAR")
else:
raise GalilError("Not all axes are referenced.")
class GalilMotorResolution(GalilSignalRO):
def _socket_get(self):
return float(
self.controller.socket_put_and_receive(f"MG stppermm[{self.parent.axis_Id_numeric}]\n")
)
class GalilMotorIsMoving(GalilSignalRO):
def _socket_get(self):
return (
self.controller.is_axis_moving(self.parent.axis_Id)
or self.controller.is_thread_active(0)
or self.controller.is_thread_active(2)
)
class GalilAxesReferenced(GalilSignalRO):
def _socket_get(self):
return self.controller.socket_put_and_receive("MG allaxref")
class GalilControllerSignal(Signal):
def _socket_get(self):
return self.controller.socket_put_and_receive("MG allaxref")
class GalilControllerDevice(Device):
motor_is_moving = Cpt(GalilMotorIsMoving, signal_name="motor_is_moving", kind="omitted")
SUB_READBACK = "motor_is_moving"
_default_sub = SUB_READBACK
def __init__(
self,
axis_Id,
prefix="",
*,
name,
kind=None,
read_attrs=None,
configuration_attrs=None,
parent=None,
host="mpc2680.psi.ch",
port=8081,
sign=1,
socket_cls=SocketIO,
**kwargs,
):
self.axis_Id = axis_Id
self.sign = sign
self.controller = GalilController(socket=socket_cls(host=host, port=port))
self.controller.set_axis(axis=self, axis_nr=0)
super().__init__(
prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
**kwargs,
)
print(self.prefix)
class GalilMotor(Device, PositionerBase):
user_readback = Cpt(
GalilReadbackSignal,
signal_name="readback",
kind="hinted",
)
user_setpoint = Cpt(GalilSetpointSignal, signal_name="setpoint")
motor_resolution = Cpt(GalilMotorResolution, signal_name="resolution", kind="config")
motor_is_moving = Cpt(GalilMotorIsMoving, signal_name="motor_is_moving", kind="omitted")
all_axes_referenced = Cpt(GalilAxesReferenced, signal_name="all_axes_referenced", kind="config")
from ophyd_devices.utils.socket import SocketMock
controller_device = Cpt(
GalilControllerDevice,
"C",
name="controller_device",
host="mpc2680.psi.ch",
port=8081,
socket_cls=SocketMock,
)
SUB_READBACK = "user_readback"
SUB_CONNECTION_CHANGE = "connection_change"
_default_sub = SUB_READBACK
def __init__(
self,
axis_Id,
prefix="",
*,
name,
kind=None,
read_attrs=None,
configuration_attrs=None,
parent=None,
host="mpc2680.psi.ch",
port=8081,
sign=1,
socket_cls=SocketIO,
**kwargs,
):
self.axis_Id = axis_Id
self.sign = sign
self.controller = GalilController(socket=socket_cls(host=host, port=port))
self.controller.set_axis(axis=self, axis_nr=self.axis_Id_numeric)
super().__init__(
prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
**kwargs,
)
self.controller.subscribe(
self._update_connection_state, event_type=self.SUB_CONNECTION_CHANGE
)
self._update_connection_state()
def _update_connection_state(self, **kwargs):
for walk in self.walk_signals():
walk.item._metadata["connected"] = self.controller.connected
@raise_if_disconnected
def move(self, position, wait=True, **kwargs):
"""Move to a specified position, optionally waiting for motion to
complete.
Parameters
----------
position
Position to move to
moved_cb : callable
Call this callback when movement has finished. This callback must
accept one keyword argument: 'obj' which will be set to this
positioner instance.
timeout : float, optional
Maximum time to wait for the motion. If None, the default timeout
for this positioner is used.
Returns
-------
status : MoveStatus
Raises
------
TimeoutError
When motion takes longer than `timeout`
ValueError
On invalid positions
RuntimeError
If motion fails other than timing out
"""
self._started_moving = False
status = super().move(position, timeout=4, **kwargs)
self.user_setpoint.put(position, wait=False)
def move_and_finish():
while self.motor_is_moving.get():
self.user_readback.read()
time.sleep(0.2)
logger.info("Move finished")
self._done_moving()
threading.Thread(target=move_and_finish, daemon=True).start()
try:
if wait:
status_wait(status)
except KeyboardInterrupt:
self.stop()
raise
return status
@property
def axis_Id(self):
return self._axis_Id_alpha
@axis_Id.setter
def axis_Id(self, val):
if isinstance(val, str):
if len(val) != 1:
raise ValueError(f"Only single-character axis_Ids are supported.")
self._axis_Id_alpha = val
self._axis_Id_numeric = ord(val.lower()) - 97
else:
raise TypeError(f"Expected value of type str but received {type(val)}")
@property
def axis_Id_numeric(self):
return self._axis_Id_numeric
@axis_Id_numeric.setter
def axis_Id_numeric(self, val):
if isinstance(val, int):
if val > 26:
raise ValueError(f"Numeric value exceeds supported range.")
self._axis_Id_alpha = val
self._axis_Id_numeric = (chr(val + 97)).capitalize()
else:
raise TypeError(f"Expected value of type int but received {type(val)}")
@property
def egu(self):
"""The engineering units (EGU) for positions"""
return "mm"
def stage(self) -> List[object]:
self.controller.on()
return super().stage()
def unstage(self) -> List[object]:
self.controller.off()
return super().unstage()
def stop(self, *, success=False):
self.controller.stop_all_axes()
return super().stop(success=success)
if __name__ == "__main__":
logging.basicConfig(level=logging.DEBUG)
mock = True
if not mock:
leyey = GalilMotor("H", name="leyey", host="mpc2680.psi.ch", port=8081, sign=-1)
leyey.stage()
status = leyey.move(0, wait=True)
status = leyey.move(10, wait=True)
leyey.read()
leyey.get()
leyey.describe()
leyey.unstage()
else:
from ophyd_devices.utils.socket import SocketMock
leyex = GalilMotor(
"G", name="leyex", host="mpc2680.psi.ch", port=8081, socket_cls=SocketMock
)
controller_device = GalilControllerDevice(
"C",
name="controller_device",
host="mpc2680.psi.ch",
port=8081,
socket_cls=SocketMock,
)
leyex.stage()
leyex.controller.galil_show_all()

View File

@ -0,0 +1 @@
from .npoint import NPointController, NPointAxis

View File

@ -0,0 +1,545 @@
import functools
import socket
import time
from ophyd_devices.utils.controller import SingletonController, threadlocked
from ophyd_devices.utils.socket import raise_if_disconnected
from prettytable import PrettyTable
from typeguard import typechecked
def channel_checked(fcn):
"""Decorator to catch attempted access to channels that are not available."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
self._check_channel(args[0])
return fcn(self, *args, **kwargs)
return wrapper
class SocketIO:
"""SocketIO helper class for TCP IP connections"""
def __init__(self, sock=None):
self.is_open = False
if sock is None:
self.open()
else:
self.sock = sock
def connect(self, host, port):
print(f"connecting to {host} port {port}")
# self.sock.create_connection((host, port))
self.sock.connect((host, port))
def _put(self, msg_bytes):
return self.sock.send(msg_bytes)
def _recv(self, buffer_length=1024):
return self.sock.recv(buffer_length)
def _initialize_socket(self):
self.sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.sock.settimeout(5)
def put(self, msg):
return self._put(msg)
def receive(self, buffer_length=1024):
return self._recv(buffer_length=buffer_length)
def open(self):
self._initialize_socket()
self.is_open = True
def close(self):
self.sock.close()
self.sock = None
self.is_open = False
class NPointController(SingletonController):
NUM_CHANNELS = 3
_read_single_loc_bit = "A0"
_write_single_loc_bit = "A2"
_trailing_bit = "55"
_range_offset = "78"
_channel_base = ["11", "83"]
def __init__(
self,
comm_socket: SocketIO,
server_ip: str = "129.129.99.87",
server_port: int = 23,
) -> None:
super().__init__()
self._server_and_port_name = (server_ip, server_port)
self.socket = comm_socket
self.connected = False
@classmethod
def create(cls):
return cls(SocketIO())
def show_all(self) -> None:
"""Display current status of all channels
Returns:
None
"""
if not self.connected:
print("npoint controller is currently disabled.")
return
print(f"Connected to controller at {self._server_and_port_name}")
t = PrettyTable()
t.field_names = ["Channel", "Range", "Position", "Target"]
for ii in range(self.NUM_CHANNELS):
t.add_row(
[
ii,
self._get_range(ii),
self._get_current_pos(ii),
self._get_target_pos(ii),
]
)
print(t)
@threadlocked
def on(self) -> None:
"""Enable the NPoint controller and open a new socket.
Raises:
TimeoutError: Raised if the socket connection raises a timeout.
Returns:
None
"""
if self.connected:
print("You are already connected to the NPoint controller.")
return
if not self.socket.is_open:
self.socket.open()
try:
self.socket.connect(self._server_and_port_name[0], self._server_and_port_name[1])
except socket.timeout:
raise TimeoutError(
f"Failed to connect to the specified server and port {self._server_and_port_name}."
)
except OSError:
print("ERROR while connecting. Let's try again")
self.socket.close()
time.sleep(0.5)
self.socket.open()
self.socket.connect(self._server_and_port_name[0], self._server_and_port_name[1])
self.connected = True
@threadlocked
def off(self) -> None:
"""Disable the controller and close the socket.
Returns:
None
"""
self.socket.close()
self.connected = False
@channel_checked
def _get_range(self, channel: int) -> int:
"""Get the range of the specified channel axis.
Args:
channel (int): Channel for which the range should be requested.
Raises:
RuntimeError: Raised if the received message doesn't have the expected number of bytes (10).
Returns:
int: Range
"""
# for first channel: 0x11 83 10 78
addr = self._channel_base.copy()
addr.extend([f"{16 + 16 * channel:x}", self._range_offset])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
if len(recvd) != 10:
raise RuntimeError(
f"Received buffer is corrupted. Expected 10 bytes and instead got {len(recvd)}"
)
device_range = self._hex_list_to_int(recvd[5:-1], signed=False)
return device_range
@channel_checked
def _get_current_pos(self, channel: int) -> float:
# for first channel: 0x11 83 13 34
addr = self._channel_base.copy()
addr.extend([f"{19 + 16 * channel:x}", "34"])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
pos_buffer = recvd[5:-1]
pos = self._hex_list_to_int(pos_buffer) / 1048574 * 100
return pos
@channel_checked
def _set_target_pos(self, channel: int, pos: float) -> None:
# for first channel: 0x11 83 12 18 00 00 00 00
addr = self._channel_base.copy()
addr.extend([f"{18 + channel * 16:x}", "18"])
target = int(round(1048574 / 100 * pos))
data = [f"{m:02x}" for m in target.to_bytes(4, byteorder="big", signed=True)]
send_buffer = self.__write_single_location_buffer(addr, data)
self._put(send_buffer)
@channel_checked
def _get_target_pos(self, channel: int) -> float:
# for first channel: 0x11 83 12 18
addr = self._channel_base.copy()
addr.extend([f"{18 + channel * 16:x}", "18"])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
pos_buffer = recvd[5:-1]
pos = self._hex_list_to_int(pos_buffer) / 1048574 * 100
return pos
@channel_checked
def _set_servo(self, channel: int, enable: bool) -> None:
print("Not tested")
return
# for first channel: 0x11 83 10 84 00 00 00 00
addr = self._channel_base.copy()
addr.extend([f"{16 + channel * 16:x}", "84"])
if enable:
data = ["00"] * 3 + ["01"]
else:
data = ["00"] * 4
send_buffer = self.__write_single_location_buffer(addr, data)
self._put(send_buffer)
@channel_checked
def _get_servo(self, channel: int) -> int:
# for first channel: 0x11 83 10 84 00 00 00 00
addr = self._channel_base.copy()
addr.extend([f"{16 + channel * 16:x}", "84"])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
buffer = recvd[5:-1]
status = self._hex_list_to_int(buffer)
return status
@threadlocked
def _put(self, buffer: list) -> None:
"""Translates a list of hex values to bytes and sends them to the socket.
Args:
buffer (list): List of hex values without leading 0x
Returns:
None
"""
buffer = b"".join([bytes.fromhex(m) for m in buffer])
self.socket.put(buffer)
@threadlocked
def _put_and_receive(self, msg_hex_list: list) -> list:
"""Send msg to socket and wait for a reply.
Args:
msg_hex_list (list): List of hex values without leading 0x.
Returns:
list: Received message as a list of hex values
"""
buffer = b"".join([bytes.fromhex(m) for m in msg_hex_list])
self.socket.put(buffer)
recv_msg = self.socket.receive()
recv_hex_list = [hex(m) for m in recv_msg]
self._verify_received_msg(msg_hex_list, recv_hex_list)
return recv_hex_list
def _verify_received_msg(self, in_list: list, out_list: list) -> None:
"""Ensure that the first address bits of sent and received messages are the same.
Args:
in_list (list): list containing the sent message
out_list (list): list containing the received message
Raises:
RuntimeError: Raised if first two address bits of 'in' and 'out' are not identical
Returns:
None
"""
# first, translate hex (str) values to int
in_list_int = [int(val, 16) for val in in_list]
out_list_int = [int(val, 16) for val in out_list]
# first ints of the reply should be the same. Otherwise something went wrong
if not in_list_int[:2] == out_list_int[:2]:
raise RuntimeError("Connection failure. Please restart the controller.")
def _check_channel(self, channel: int) -> None:
if channel >= self.NUM_CHANNELS:
raise ValueError(
f"Channel {channel+1} exceeds the available number of channels ({self.NUM_CHANNELS})"
)
@staticmethod
def _hex_list_to_int(in_buffer: list, byteorder="little", signed=True) -> int:
"""Translate hex list to int.
Args:
in_buffer (list): Input buffer; received as list of hex values
byteorder (str, optional): Byteorder of in_buffer. Defaults to "little".
signed (bool, optional): Whether the hex list represents a signed int. Defaults to True.
Returns:
int: Translated integer.
"""
if byteorder == "little":
in_buffer.reverse()
# make sure that all hex strings have the same format ("FF")
val_hex = [f"{int(m, 16):02x}" for m in in_buffer]
val_bytes = [bytes.fromhex(m) for m in val_hex]
val = int.from_bytes(b"".join(val_bytes), byteorder="big", signed=signed)
return val
@staticmethod
def __read_single_location_buffer(addr) -> list:
"""Prepare buffer for reading from a single memory location (hex address).
Number of bytes: 6
Format: 0xA0 [addr] 0x55
Return Value: 0xA0 [addr] [data] 0x55
Sample Hex Transmission from PC to LC.400: A0 18 12 83 11 55
Sample Hex Return Transmission from LC.400 to PC: A0 18 12 83 11 64 00 00 00 55
Args:
addr (list): Hex address to read from
Returns:
list: List of hex values representing the read instruction.
"""
buffer = []
buffer.append(NPointController._read_single_loc_bit)
if isinstance(addr, list):
addr.reverse()
buffer.extend(addr)
else:
buffer.append(addr)
buffer.append(NPointController._trailing_bit)
return buffer
@staticmethod
def __write_single_location_buffer(addr: list, data: list) -> list:
"""Prepare buffer for writing to a single memory location (hex address).
Number of bytes: 10
Format: 0xA2 [addr] [data] 0x55
Return Value: none
Sample Hex Transmission from PC to C.400: A2 18 12 83 11 E8 03 00 00 55
Args:
addr (list): List of hex values representing the address to write to.
data (list): List of hex values representing the data that should be written.
Returns:
list: List of hex values representing the write instruction.
"""
buffer = []
buffer.append(NPointController._write_single_loc_bit)
if isinstance(addr, list):
addr.reverse()
buffer.extend(addr)
else:
buffer.append(addr)
if isinstance(data, list):
data.reverse()
buffer.extend(data)
else:
buffer.append(data)
buffer.append(NPointController._trailing_bit)
return buffer
@staticmethod
def __read_array():
raise NotImplementedError
@staticmethod
def __write_next_command():
raise NotImplementedError
def __del__(self):
if self.connected:
print("Closing npoint socket")
self.off()
class NPointAxis:
def __init__(self, controller: NPointController, channel: int, name: str) -> None:
super().__init__()
self._axis_range = 100
self.controller = controller
self.channel = channel
self.name = name
self.controller._check_channel(channel)
self._settling_time = 0.1
if self.settling_time == 0:
self.settling_time = 0.1
print(f"Setting the npoint settling time to {self.settling_time:.2f} s.")
print(
"You can set the settling time depending on the stage tuning\nusing the settling_time property."
)
print("This is the waiting time before the counting is done.")
def show_all(self) -> None:
self.controller.show_all()
@raise_if_disconnected
def get(self) -> float:
"""Get current position for this channel.
Raises:
RuntimeError: Raised if channel is not connected.
Returns:
float: position
"""
return self.controller._get_current_pos(self.channel)
@raise_if_disconnected
def get_target_pos(self) -> float:
"""Get target position for this channel.
Raises:
RuntimeError: Raised if channel is not connected.
Returns:
float: position
"""
return self.controller._get_target_pos(self.channel)
@raise_if_disconnected
@typechecked
def set(self, pos: float) -> None:
"""Set a new target position and wait until settled (settling_time).
Args:
pos (float): New target position
Raises:
RuntimeError: Raised if channel is not connected.
Returns:
None
"""
self.controller._set_target_pos(self.channel, pos)
time.sleep(self.settling_time)
@property
def connected(self) -> bool:
return self.controller.connected
@property
@raise_if_disconnected
def servo(self) -> int:
"""Get servo status
Raises:
RuntimeError: Raised if channel is not connected.
Returns:
int: Servo status
"""
return self.controller._get_servo(self.channel)
@servo.setter
@raise_if_disconnected
@typechecked
def servo(self, val: bool) -> None:
"""Set servo status
Args:
val (bool): Servo status
Raises:
RuntimeError: Raised if channel is not connected.
Returns:
None
"""
self.controller._set_servo(self.channel, val)
@property
def settling_time(self) -> float:
return self._settling_time
@settling_time.setter
@typechecked
def settling_time(self, val: float) -> None:
self._settling_time = val
print(f"Setting the npoint settling time to {val:.2f} s.")
class NPointEpics(NPointAxis):
def __init__(self, controller: NPointController, channel: int, name: str) -> None:
super().__init__(controller, channel, name)
self.low_limit = -50
self.high_limit = 50
self._prefix = name
def get_pv(self) -> str:
return self.name
def get_position(self, readback=True) -> float:
if readback:
return self.get()
else:
return self.get_target_pos()
def within_limits(self, pos: float) -> bool:
return pos > self.low_limit and pos < self.high_limit
def move(self, position: float, wait=True) -> None:
self.set(position)
if __name__ == "__main__":
## EXAMPLES ##
#
# Create controller and socket instance explicitly:
# controller = NPointController(SocketIO())
# npointx = NPointAxis(controller, 0, "nx")
# npointy = NPointAxis(controller, 1, "ny")
# Create controller instance explicitly
# controller = NPointController.create()
# npointx = NPointAxis(controller, 0, "nx")
# npointy = NPointAxis(controller, 1, "ny")
# Single-line axis:
# npointx = NPointAxis(NPointController.create(), 0, "nx")
#
# EPICS wrapper:
# nx = NPointEpics(NPointController.create(), 0, "nx")
controller = NPointController.create()
npointx = NPointAxis(NPointController.create(), 0, "nx")
npointy = NPointAxis(NPointController.create(), 0, "ny")

View File

@ -0,0 +1,434 @@
import abc
import socket
import functools
import time
import threading
from typeguard import typechecked
from ophyd import PositionerBase, Signal
from ophyd.device import Device, Component as Cpt
from prettytable import PrettyTable
from ophyd_devices.utils.socket import raise_if_disconnected
from ophyd_devices.utils.controller import SingletonController
def channel_checked(fcn):
"""Decorator to catch attempted access to channels that are not available."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
self._check_channel(args[0])
return fcn(self, *args, **kwargs)
return wrapper
def threadlocked(fcn):
"""Ensure that thread acquires and releases the lock."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
with self._lock:
return fcn(self, *args, **kwargs)
return wrapper
class NPointController(SingletonController):
NUM_CHANNELS = 3
_read_single_loc_bit = "A0"
_write_single_loc_bit = "A2"
_trailing_bit = "55"
_range_offset = "78"
_channel_base = ["11", "83"]
def __init__(
self,
comm_socket: SocketIO,
server_ip: str = "129.129.99.87",
server_port: int = 23,
) -> None:
super().__init__()
self._server_and_port_name = (server_ip, server_port)
self.socket = comm_socket
self.connected = False
@classmethod
def create(cls):
return cls(SocketIO())
def show_all(self) -> None:
"""Display current status of all channels
Returns:
None
"""
if not self.connected:
print("npoint controller is currently disabled.")
return
print(f"Connected to controller at {self._server_and_port_name}")
t = PrettyTable()
t.field_names = ["Channel", "Range", "Position", "Target"]
for ii in range(self.NUM_CHANNELS):
t.add_row(
[
ii,
self._get_range(ii),
self._get_current_pos(ii),
self._get_target_pos(ii),
]
)
print(t)
@threadlocked
def on(self) -> None:
"""Enable the NPoint controller and open a new socket.
Raises:
TimeoutError: Raised if the socket connection raises a timeout.
Returns:
None
"""
if self.connected:
print("You are already connected to the NPoint controller.")
return
if not self.socket.is_open:
self.socket.open()
try:
self.socket.connect(
self._server_and_port_name[0], self._server_and_port_name[1]
)
except socket.timeout:
raise TimeoutError(
f"Failed to connect to the specified server and port {self._server_and_port_name}."
)
except OSError:
print("ERROR while connecting. Let's try again")
self.socket.close()
time.sleep(0.5)
self.socket.open()
self.socket.connect(
self._server_and_port_name[0], self._server_and_port_name[1]
)
self.connected = True
@threadlocked
def off(self) -> None:
"""Disable the controller and close the socket.
Returns:
None
"""
self.socket.close()
self.connected = False
@channel_checked
def _get_range(self, channel: int) -> int:
"""Get the range of the specified channel axis.
Args:
channel (int): Channel for which the range should be requested.
Raises:
RuntimeError: Raised if the received message doesn't have the expected number of bytes (10).
Returns:
int: Range
"""
# for first channel: 0x11 83 10 78
addr = self._channel_base.copy()
addr.extend([f"{16 + 16 * channel:x}", self._range_offset])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
if len(recvd) != 10:
raise RuntimeError(
f"Received buffer is corrupted. Expected 10 bytes and instead got {len(recvd)}"
)
device_range = self._hex_list_to_int(recvd[5:-1], signed=False)
return device_range
@channel_checked
def _get_current_pos(self, channel: int) -> float:
# for first channel: 0x11 83 13 34
addr = self._channel_base.copy()
addr.extend([f"{19 + 16 * channel:x}", "34"])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
pos_buffer = recvd[5:-1]
pos = self._hex_list_to_int(pos_buffer) / 1048574 * 100
return pos
@channel_checked
def _set_target_pos(self, channel: int, pos: float) -> None:
# for first channel: 0x11 83 12 18 00 00 00 00
addr = self._channel_base.copy()
addr.extend([f"{18 + channel * 16:x}", "18"])
target = int(round(1048574 / 100 * pos))
data = [f"{m:02x}" for m in target.to_bytes(4, byteorder="big", signed=True)]
send_buffer = self.__write_single_location_buffer(addr, data)
self._put(send_buffer)
@channel_checked
def _get_target_pos(self, channel: int) -> float:
# for first channel: 0x11 83 12 18
addr = self._channel_base.copy()
addr.extend([f"{18 + channel * 16:x}", "18"])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
pos_buffer = recvd[5:-1]
pos = self._hex_list_to_int(pos_buffer) / 1048574 * 100
return pos
@channel_checked
def _set_servo(self, channel: int, enable: bool) -> None:
print("Not tested")
return
# for first channel: 0x11 83 10 84 00 00 00 00
addr = self._channel_base.copy()
addr.extend([f"{16 + channel * 16:x}", "84"])
if enable:
data = ["00"] * 3 + ["01"]
else:
data = ["00"] * 4
send_buffer = self.__write_single_location_buffer(addr, data)
self._put(send_buffer)
@channel_checked
def _get_servo(self, channel: int) -> int:
# for first channel: 0x11 83 10 84 00 00 00 00
addr = self._channel_base.copy()
addr.extend([f"{16 + channel * 16:x}", "84"])
send_buffer = self.__read_single_location_buffer(addr)
recvd = self._put_and_receive(send_buffer)
buffer = recvd[5:-1]
status = self._hex_list_to_int(buffer)
return status
@threadlocked
def _put(self, buffer: list) -> None:
"""Translates a list of hex values to bytes and sends them to the socket.
Args:
buffer (list): List of hex values without leading 0x
Returns:
None
"""
buffer = b"".join([bytes.fromhex(m) for m in buffer])
self.socket.put(buffer)
@threadlocked
def _put_and_receive(self, msg_hex_list: list) -> list:
"""Send msg to socket and wait for a reply.
Args:
msg_hex_list (list): List of hex values without leading 0x.
Returns:
list: Received message as a list of hex values
"""
buffer = b"".join([bytes.fromhex(m) for m in msg_hex_list])
self.socket.put(buffer)
recv_msg = self.socket.receive()
recv_hex_list = [hex(m) for m in recv_msg]
self._verify_received_msg(msg_hex_list, recv_hex_list)
return recv_hex_list
def _verify_received_msg(self, in_list: list, out_list: list) -> None:
"""Ensure that the first address bits of sent and received messages are the same.
Args:
in_list (list): list containing the sent message
out_list (list): list containing the received message
Raises:
RuntimeError: Raised if first two address bits of 'in' and 'out' are not identical
Returns:
None
"""
# first, translate hex (str) values to int
in_list_int = [int(val, 16) for val in in_list]
out_list_int = [int(val, 16) for val in out_list]
# first ints of the reply should be the same. Otherwise something went wrong
if not in_list_int[:2] == out_list_int[:2]:
raise RuntimeError("Connection failure. Please restart the controller.")
def _check_channel(self, channel: int) -> None:
if channel >= self.NUM_CHANNELS:
raise ValueError(
f"Channel {channel+1} exceeds the available number of channels ({self.NUM_CHANNELS})"
)
@staticmethod
def _hex_list_to_int(in_buffer: list, byteorder="little", signed=True) -> int:
"""Translate hex list to int.
Args:
in_buffer (list): Input buffer; received as list of hex values
byteorder (str, optional): Byteorder of in_buffer. Defaults to "little".
signed (bool, optional): Whether the hex list represents a signed int. Defaults to True.
Returns:
int: Translated integer.
"""
if byteorder == "little":
in_buffer.reverse()
# make sure that all hex strings have the same format ("FF")
val_hex = [f"{int(m, 16):02x}" for m in in_buffer]
val_bytes = [bytes.fromhex(m) for m in val_hex]
val = int.from_bytes(b"".join(val_bytes), byteorder="big", signed=signed)
return val
@staticmethod
def __read_single_location_buffer(addr) -> list:
"""Prepare buffer for reading from a single memory location (hex address).
Number of bytes: 6
Format: 0xA0 [addr] 0x55
Return Value: 0xA0 [addr] [data] 0x55
Sample Hex Transmission from PC to LC.400: A0 18 12 83 11 55
Sample Hex Return Transmission from LC.400 to PC: A0 18 12 83 11 64 00 00 00 55
Args:
addr (list): Hex address to read from
Returns:
list: List of hex values representing the read instruction.
"""
buffer = []
buffer.append(NPointController._read_single_loc_bit)
if isinstance(addr, list):
addr.reverse()
buffer.extend(addr)
else:
buffer.append(addr)
buffer.append(NPointController._trailing_bit)
return buffer
@staticmethod
def __write_single_location_buffer(addr: list, data: list) -> list:
"""Prepare buffer for writing to a single memory location (hex address).
Number of bytes: 10
Format: 0xA2 [addr] [data] 0x55
Return Value: none
Sample Hex Transmission from PC to C.400: A2 18 12 83 11 E8 03 00 00 55
Args:
addr (list): List of hex values representing the address to write to.
data (list): List of hex values representing the data that should be written.
Returns:
list: List of hex values representing the write instruction.
"""
buffer = []
buffer.append(NPointController._write_single_loc_bit)
if isinstance(addr, list):
addr.reverse()
buffer.extend(addr)
else:
buffer.append(addr)
if isinstance(data, list):
data.reverse()
buffer.extend(data)
else:
buffer.append(data)
buffer.append(NPointController._trailing_bit)
return buffer
@staticmethod
def __read_array():
raise NotImplementedError
@staticmethod
def __write_next_command():
raise NotImplementedError
def __del__(self):
if self.connected:
print("Closing npoint socket")
self.off()
class SocketSignal(abc.ABC, Signal):
def __init__(self, *, name, **kwargs):
super().__init__(**kwargs)
@abc.abstractmethod
def _socket_get(self):
...
@abc.abstractmethod
def _socket_set(self, val):
...
class NPointSignalBase(SocketSignal):
def __init__(self, controller, signal_name, **kwargs):
self.controller = controller
self.signal_name = signal_name
super().__init__(**kwargs)
class NPointReadbackSignal(NPointSignalBase):
def _socket_get(self):
pass
def _socket_set(self, val):
pass
class NPointAxis(Device, PositionerBase):
def __init__(
self,
prefix="",
*,
name,
channel=None,
kind=None,
read_attrs=None,
configuration_attrs=None,
parent=None,
**kwargs,
):
self.channel = channel
self.controller = self._get_controller()
self.readback = Cpt(
NPointSignal, controller=self.controller, signal_name="RBV", kind="hinted"
)
self.user_setpoint = Cpt(
NPointSignal, controller=self.controller, signal_name="VAL", kind="normal"
)
self.motor_resolution = Cpt(
NPointSignal, controller=self.controller, signal_name="RNGE", kind="config"
)
self.motor_is_moving = Cpt(
NPointSignal, controller=self.controller, signal_name="MOVN", kind="config"
)
self.axes_referenced = Cpt(
NPointSignal, controller=self.controller, signal_name="XREF", kind="config"
)
def _get_controller(self):
return NPointController()

View File

@ -0,0 +1 @@
from .rt_lamni_ophyd import RtLamniMotor, RtLamniController

View File

@ -0,0 +1,442 @@
import functools
import threading
import time
import numpy as np
from typing import List
from ophyd import PositionerBase, Device, Component as Cpt
from prettytable import PrettyTable
from ophyd_devices.utils.controller import Controller
from ophyd_devices.utils.socket import (
SocketIO,
raise_if_disconnected,
SocketSignal,
)
import logging
from ophyd.utils import ReadOnlyError
from ophyd.status import wait as status_wait
logger = logging.getLogger("rtlamni")
def threadlocked(fcn):
"""Ensure that thread acquires and releases the lock."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
with self._lock:
return fcn(self, *args, **kwargs)
return wrapper
class RtLamniCommunicationError(Exception):
pass
class RtLamniError(Exception):
pass
def retry_once(fcn):
"""Decorator to rerun a function in case a CommunicationError was raised. This may happen if the buffer was not empty."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
try:
val = fcn(self, *args, **kwargs)
except (RtLamniCommunicationError, RtLamniError):
val = fcn(self, *args, **kwargs)
return val
return wrapper
class RtLamniController(Controller):
USER_ACCESS = [
"socket_put_and_receive",
"set_rotation_angle"
]
def __init__(
self,
*,
name="RtLamniController",
kind=None,
parent=None,
socket=None,
attr_name="",
labels=None,
):
if not hasattr(self, "_initialized") or not self._initialized:
self._rtlamni_axis_per_controller = 3
self._axis = [None for axis_num in range(self._rtlamni_axis_per_controller)]
super().__init__(
name=name,
socket=socket,
attr_name=attr_name,
parent=parent,
labels=labels,
kind=kind,
)
def on(self, controller_num=0) -> None:
"""Open a new socket connection to the controller"""
if not self.connected:
self.sock.open()
#discuss - after disconnect takes a while for the server to be ready again
welcome_message = self.sock.receive()
self.connected = True
else:
logger.info("The connection has already been established.")
# warnings.warn(f"The connection has already been established.", stacklevel=2)
def off(self) -> None:
"""Close the socket connection to the controller"""
if self.connected:
self.sock.close()
self.connected = False
else:
logger.info("The connection is already closed.")
def set_axis(self, axis: Device, axis_nr: int) -> None:
"""Assign an axis to a device instance.
Args:
axis (Device): Device instance (e.g. GalilMotor)
axis_nr (int): Controller axis number
"""
self._axis[axis_nr] = axis
def socket_put(self, val: str) -> None:
self.sock.put(f"{val}\n".encode())
def socket_get(self) -> str:
return self.sock.receive().decode()
@retry_once
@threadlocked
def socket_put_and_receive(self, val: str, remove_trailing_chars=True) -> str:
self.socket_put(val)
if remove_trailing_chars:
return self._remove_trailing_characters(self.sock.receive().decode())
return self.socket_get()
def is_axis_moving(self, axis_Id) -> bool:
#this checks that axis is on target
axis_is_on_target = bool(float(self.socket_put_and_receive(f"o")))
return not axis_is_on_target
# def is_thread_active(self, thread_id: int) -> bool:
# val = float(self.socket_put_and_receive(f"MG_XQ{thread_id}"))
# if val == -1:
# return False
# return True
def _remove_trailing_characters(self, var) -> str:
if len(var) > 1:
return var.split("\r\n")[0]
return var
def set_rotation_angle(self, val:float):
self.socket_put(f"a{(val-300+30.538)/180*np.pi}")
def stop_all_axes(self) -> str:
return 0 #self.socket_put_and_receive(f"XQ#STOP,1")
class RtLamniSignalBase(SocketSignal):
def __init__(self, signal_name, **kwargs):
self.signal_name = signal_name
super().__init__(**kwargs)
self.controller = self.parent.controller
self.sock = self.parent.controller.sock
class RtLamniSignalRO(RtLamniSignalBase):
def __init__(self, signal_name, **kwargs):
super().__init__(signal_name, **kwargs)
self._metadata["write_access"] = False
def _socket_set(self, val):
raise ReadOnlyError("Read-only signals cannot be set")
class RtLamniReadbackSignal(RtLamniSignalRO):
@retry_once
def _socket_get(self) -> float:
"""Get command for the readback signal
Returns:
float: Readback value after adjusting for sign and motor resolution.
"""
return_table = (self.controller.socket_put_and_receive(f"J4")).split(",")
print(return_table)
if self.parent.axis_Id_numeric == 0:
readback_index = 2
elif self.parent.axis_Id_numeric == 1:
readback_index = 1
else:
raise RtLamniError("Currently, only two axes are supported.")
current_pos = float(return_table[readback_index])
current_pos *= self.parent.sign
return current_pos
class RtLamniSetpointSignal(RtLamniSignalBase):
setpoint = 0
def _socket_get(self) -> float:
"""Get command for receiving the setpoint / target value.
The value is not pulled from the controller but instead just the last setpoint used.
Returns:
float: setpoint / target value
"""
return self.setpoint
@retry_once
def _socket_set(self, val: float) -> None:
"""Set a new target value / setpoint value. Before submission, the target value is adjusted for the axis' sign.
Furthermore, it is ensured that all axes are referenced before a new setpoint is submitted.
Args:
val (float): Target value / setpoint value
Raises:
RtLamniError: Raised if interferometer feedback is disabled.
"""
target_val = val * self.parent.sign
self.setpoint = target_val
interferometer_feedback_not_running = int((self.controller.socket_put_and_receive("J2")).split(",")[0])
if interferometer_feedback_not_running == 0:
self.controller.socket_put(f"pa{self.parent.axis_Id_numeric},{target_val:.4f}")
else:
raise RtLamniError("The interferometer feedback is not running. Either it is turned off or and interferometer error occured.")
class RtLamniMotorIsMoving(RtLamniSignalRO):
def _socket_get(self):
return 0
def get(self):
val = super().get()
if val is not None:
self._run_subs(sub_type=self.SUB_VALUE,
value=val,
timestamp=time.time(),
)
return val
class RtLamniFeedbackRunning(RtLamniSignalRO):
def _socket_get(self):
if int((self.controller.socket_put_and_receive("J2")).split(",")[0]) == 0:
return 1
else:
return 0
class RtLamniMotor(Device, PositionerBase):
USER_ACCESS = [
"controller"
]
readback = Cpt(
RtLamniReadbackSignal,
signal_name="readback",
kind="hinted",
)
user_setpoint = Cpt(RtLamniSetpointSignal, signal_name="setpoint")
motor_is_moving = Cpt(
RtLamniMotorIsMoving, signal_name="motor_is_moving", kind="normal"
)
SUB_READBACK = "readback"
SUB_CONNECTION_CHANGE = "connection_change"
_default_sub = SUB_READBACK
def __init__(
self,
axis_Id,
prefix="",
*,
name,
kind=None,
read_attrs=None,
configuration_attrs=None,
parent=None,
host="mpc2680.psi.ch",
port=3333,
sign=1,
socket_cls=SocketIO,
**kwargs,
):
self.axis_Id = axis_Id
self.sign = sign
self.controller = RtLamniController(socket=socket_cls(host=host, port=port))
self.controller.set_axis(axis=self, axis_nr=self.axis_Id_numeric)
self.tolerance = kwargs.pop("tolerance", 0.5)
super().__init__(
prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
**kwargs,
)
self.readback.name = self.name
self.controller.subscribe(
self._update_connection_state, event_type=self.SUB_CONNECTION_CHANGE
)
self._update_connection_state()
# self.readback.subscribe(self._forward_readback, event_type=self.readback.SUB_VALUE)
def _update_connection_state(self, **kwargs):
for walk in self.walk_signals():
walk.item._metadata["connected"] = self.controller.connected
def _forward_readback(self, **kwargs):
kwargs.pop("sub_type")
self._run_subs(sub_type="readback", **kwargs)
@raise_if_disconnected
def move(self, position, wait=True, **kwargs):
"""Move to a specified position, optionally waiting for motion to
complete.
Parameters
----------
position
Position to move to
moved_cb : callable
Call this callback when movement has finished. This callback must
accept one keyword argument: 'obj' which will be set to this
positioner instance.
timeout : float, optional
Maximum time to wait for the motion. If None, the default timeout
for this positioner is used.
Returns
-------
status : MoveStatus
Raises
------
TimeoutError
When motion takes longer than `timeout`
ValueError
On invalid positions
RuntimeError
If motion fails other than timing out
"""
self._started_moving = False
timeout = kwargs.pop("timeout", 4)
status = super().move(position, timeout=timeout, **kwargs)
self.user_setpoint.put(position, wait=False)
def move_and_finish():
while self.motor_is_moving.get():
logger.info("motor is moving")
val = self.readback.read()
self._run_subs(sub_type=self.SUB_READBACK,
value=val,
timestamp=time.time(),
)
time.sleep(0.01)
logger.info("Move finished")
self._done_moving()
threading.Thread(target=move_and_finish, daemon=True).start()
try:
if wait:
status_wait(status)
except KeyboardInterrupt:
self.stop()
raise
return status
@property
def axis_Id(self):
return self._axis_Id_alpha
@axis_Id.setter
def axis_Id(self, val):
if isinstance(val, str):
if len(val) != 1:
raise ValueError(f"Only single-character axis_Ids are supported.")
self._axis_Id_alpha = val
self._axis_Id_numeric = ord(val.lower()) - 97
else:
raise TypeError(f"Expected value of type str but received {type(val)}")
@property
def axis_Id_numeric(self):
return self._axis_Id_numeric
@axis_Id_numeric.setter
def axis_Id_numeric(self, val):
if isinstance(val, int):
if val > 26:
raise ValueError(f"Numeric value exceeds supported range.")
self._axis_Id_alpha = val
self._axis_Id_numeric = (chr(val + 97)).capitalize()
else:
raise TypeError(f"Expected value of type int but received {type(val)}")
@property
def egu(self):
"""The engineering units (EGU) for positions"""
return "um"
# how is this used later?
def stage(self) -> List[object]:
self.controller.on()
return super().stage()
def unstage(self) -> List[object]:
self.controller.off()
return super().unstage()
def stop(self, *, success=False):
self.controller.stop_all_axes()
return super().stop(success=success)
if __name__ == "__main__":
logging.basicConfig(level=logging.DEBUG)
mock = False
if not mock:
rty = RtLamniMotor("B", name="rty", host="mpc2680.psi.ch", port=3333, sign=1)
rty.stage()
status = rty.move(0, wait=True)
status = rty.move(10, wait=True)
rty.read()
rty.get()
rty.describe()
rty.unstage()
else:
from ophyd_devices.utils.socket import SocketMock
rtx = RtLamniMotor(
"A", name="rtx", host="mpc2680.psi.ch", port=3333, socket_cls=SocketMock
)
rty = RtLamniMotor(
"B", name="rty", host="mpc2680.psi.ch", port=3333, socket_cls=SocketMock
)
rtx.stage()
# rty.stage()

View File

@ -0,0 +1 @@
from .sim import SynAxisMonitor, SynAxisOPAAS

409
ophyd_devices/sim/sim.py Normal file
View File

@ -0,0 +1,409 @@
import threading
import time as ttime
import warnings
import numpy as np
from ophyd import Component as Cpt
from ophyd import Device, DeviceStatus, PositionerBase, Signal
from ophyd.sim import _ReadbackSignal, _SetpointSignal
from ophyd.utils import LimitError, ReadOnlyError
class DeviceStop(Exception):
pass
class _ReadbackSignal(Signal):
def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
self._metadata.update(
connected=True,
write_access=False,
)
def get(self):
self._readback = self.parent.sim_state["readback"]
return self._readback
def describe(self):
res = super().describe()
# There should be only one key here, but for the sake of
# generality....
for k in res:
res[k]["precision"] = self.parent.precision
return res
@property
def timestamp(self):
"""Timestamp of the readback value"""
return self.parent.sim_state["readback_ts"]
def put(self, value, *, timestamp=None, force=False):
raise ReadOnlyError("The signal {} is readonly.".format(self.name))
def set(self, value, *, timestamp=None, force=False):
raise ReadOnlyError("The signal {} is readonly.".format(self.name))
class _ReadbackSignalRand(Signal):
def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
self._metadata.update(
connected=True,
write_access=False,
)
def get(self):
self._readback = np.random.rand()
return self._readback
def describe(self):
res = super().describe()
# There should be only one key here, but for the sake of
# generality....
for k in res:
res[k]["precision"] = self.parent.precision
return res
@property
def timestamp(self):
"""Timestamp of the readback value"""
return self.parent.sim_state["readback_ts"]
def put(self, value, *, timestamp=None, force=False):
raise ReadOnlyError("The signal {} is readonly.".format(self.name))
def set(self, value, *, timestamp=None, force=False):
raise ReadOnlyError("The signal {} is readonly.".format(self.name))
class _SetpointSignal(Signal):
def put(self, value, *, timestamp=None, force=False):
self._readback = float(value)
self.parent.set(float(value))
def get(self):
self._readback = self.parent.sim_state["setpoint"]
return self.parent.sim_state["setpoint"]
def describe(self):
res = super().describe()
# There should be only one key here, but for the sake of generality....
for k in res:
res[k]["precision"] = self.parent.precision
return res
@property
def timestamp(self):
"""Timestamp of the readback value"""
return self.parent.sim_state["setpoint_ts"]
class _IsMovingSignal(Signal):
def put(self, value, *, timestamp=None, force=False):
self._readback = float(value)
self.parent.set(float(value))
def get(self):
self._readback = self.parent.sim_state["is_moving"]
return self.parent.sim_state["is_moving"]
def describe(self):
res = super().describe()
# There should be only one key here, but for the sake of generality....
for k in res:
res[k]["precision"] = self.parent.precision
return res
@property
def timestamp(self):
"""Timestamp of the readback value"""
return self.parent.sim_state["is_moving_ts"]
class SynAxisMonitor(Device):
"""
A synthetic settable Device mimic any 1D Axis (position, temperature).
Parameters
----------
name : string, keyword only
readback_func : callable, optional
When the Device is set to ``x``, its readback will be updated to
``f(x)``. This can be used to introduce random noise or a systematic
offset.
Expected signature: ``f(x) -> value``.
value : object, optional
The initial value. Default is 0.
delay : number, optional
Simulates how long it takes the device to "move". Default is 0 seconds.
precision : integer, optional
Digits of precision. Default is 3.
parent : Device, optional
Used internally if this Signal is made part of a larger Device.
kind : a member the Kind IntEnum (or equivalent integer), optional
Default is Kind.normal. See Kind for options.
"""
readback = Cpt(_ReadbackSignalRand, value=0, kind="hinted")
SUB_READBACK = "readback"
_default_sub = SUB_READBACK
def __init__(
self,
*,
name,
readback_func=None,
value=0,
delay=0,
precision=3,
parent=None,
labels=None,
kind=None,
**kwargs,
):
if readback_func is None:
def readback_func(x):
return x
sentinel = object()
loop = kwargs.pop("loop", sentinel)
if loop is not sentinel:
warnings.warn(
f"{self.__class__} no longer takes a loop as input. "
"Your input will be ignored and may raise in the future",
stacklevel=2,
)
self.sim_state = {}
self._readback_func = readback_func
self.delay = delay
self.precision = precision
self.tolerance = kwargs.pop("tolerance", 0.5)
# initialize values
self.sim_state["readback"] = readback_func(value)
self.sim_state["readback_ts"] = ttime.time()
super().__init__(name=name, parent=parent, labels=labels, kind=kind, **kwargs)
self.readback.name = self.name
class DummyController:
USER_ACCESS = ["some_var", "controller_show_all"]
some_var = 10
another_var = 20
def controller_show_all(self):
"""dummy controller show all
Raises:
in: _description_
LimitError: _description_
Returns:
_type_: _description_
"""
print(self.some_var)
class SynAxisOPAAS(Device, PositionerBase):
"""
A synthetic settable Device mimic any 1D Axis (position, temperature).
Parameters
----------
name : string, keyword only
readback_func : callable, optional
When the Device is set to ``x``, its readback will be updated to
``f(x)``. This can be used to introduce random noise or a systematic
offset.
Expected signature: ``f(x) -> value``.
value : object, optional
The initial value. Default is 0.
delay : number, optional
Simulates how long it takes the device to "move". Default is 0 seconds.
precision : integer, optional
Digits of precision. Default is 3.
parent : Device, optional
Used internally if this Signal is made part of a larger Device.
kind : a member the Kind IntEnum (or equivalent integer), optional
Default is Kind.normal. See Kind for options.
"""
USER_ACCESS = ["sim_state", "readback", "speed", "dummy_controller"]
readback = Cpt(_ReadbackSignal, value=0, kind="hinted")
setpoint = Cpt(_SetpointSignal, value=0, kind="normal")
motor_is_moving = Cpt(_IsMovingSignal, value=0, kind="normal")
velocity = Cpt(Signal, value=1, kind="config")
acceleration = Cpt(Signal, value=1, kind="config")
high_limit_travel = Cpt(Signal, value=0, kind="omitted")
low_limit_travel = Cpt(Signal, value=0, kind="omitted")
unused = Cpt(Signal, value=1, kind="omitted")
SUB_READBACK = "readback"
_default_sub = SUB_READBACK
def __init__(
self,
*,
name,
readback_func=None,
value=0,
delay=0,
speed=1,
update_frequency=2,
precision=3,
parent=None,
labels=None,
kind=None,
limits=None,
**kwargs,
):
if readback_func is None:
def readback_func(x):
return x
sentinel = object()
loop = kwargs.pop("loop", sentinel)
if loop is not sentinel:
warnings.warn(
f"{self.__class__} no longer takes a loop as input. "
"Your input will be ignored and may raise in the future",
stacklevel=2,
)
self.sim_state = {}
self._readback_func = readback_func
self.delay = delay
self.precision = precision
self.speed = speed
self.update_frequency = update_frequency
self.tolerance = kwargs.pop("tolerance", 0.05)
self._stopped = False
self.dummy_controller = DummyController()
# initialize values
self.sim_state["setpoint"] = value
self.sim_state["setpoint_ts"] = ttime.time()
self.sim_state["readback"] = readback_func(value)
self.sim_state["readback_ts"] = ttime.time()
self.sim_state["is_moving"] = 0
self.sim_state["is_moving_ts"] = ttime.time()
super().__init__(name=name, parent=parent, labels=labels, kind=kind, **kwargs)
self.readback.name = self.name
if limits is not None:
assert len(limits) == 2
self.low_limit_travel.put(limits[0])
self.high_limit_travel.put(limits[1])
@property
def limits(self):
return (self.low_limit_travel.get(), self.high_limit_travel.get())
@property
def low_limit(self):
return self.limits[0]
@property
def high_limit(self):
return self.limits[1]
def check_value(self, pos):
"""Check that the position is within the soft limits"""
low_limit, high_limit = self.limits
if low_limit < high_limit and not (low_limit <= pos <= high_limit):
raise LimitError(f"position={pos} not within limits {self.limits}")
def set(self, value):
self.check_value(value)
old_setpoint = self.sim_state["setpoint"]
self.sim_state["is_moving"] = 1
self.motor_is_moving._run_subs(
sub_type=self.motor_is_moving.SUB_VALUE,
old_value=0,
value=1,
timestamp=self.sim_state["is_moving_ts"],
)
self.sim_state["setpoint"] = value
self.sim_state["setpoint_ts"] = ttime.time()
self.setpoint._run_subs(
sub_type=self.setpoint.SUB_VALUE,
old_value=old_setpoint,
value=self.sim_state["setpoint"],
timestamp=self.sim_state["setpoint_ts"],
)
def update_state(val):
if self._stopped:
raise DeviceStop
old_readback = self.sim_state["readback"]
self.sim_state["readback"] = val
self.sim_state["readback_ts"] = ttime.time()
self.readback._run_subs(
sub_type=self.readback.SUB_VALUE,
old_value=old_readback,
value=self.sim_state["readback"],
timestamp=self.sim_state["readback_ts"],
)
self._run_subs(
sub_type=self.SUB_READBACK,
old_value=old_readback,
value=self.sim_state["readback"],
timestamp=self.sim_state["readback_ts"],
)
st = DeviceStatus(device=self)
if self.delay:
def move_and_finish():
success = True
try:
move_val = self.sim_state["setpoint"] + self.tolerance * np.random.uniform(
-1, 1
)
updates = np.ceil(
np.abs(old_setpoint - move_val) / self.speed * self.update_frequency
)
for ii in np.linspace(old_setpoint, move_val - 5, int(updates)):
ttime.sleep(1 / self.update_frequency)
update_state(ii)
update_state(move_val)
self.sim_state["is_moving"] = 0
self.sim_state["is_moving_ts"] = ttime.time()
self.motor_is_moving._run_subs(
sub_type=self.motor_is_moving.SUB_VALUE,
old_value=1,
value=0,
timestamp=self.sim_state["is_moving_ts"],
)
except DeviceStop:
self._stopped = False
success = False
self._done_moving(success=success)
st.set_finished()
threading.Thread(target=move_and_finish, daemon=True).start()
# raise TimeoutError
else:
update_state(value)
self._done_moving()
return st
def stop(self, *, success=False):
super().stop(success=success)
self._stopped = True
@property
def position(self):
return self.readback.get()
def egu(self):
return "mm"

View File

@ -0,0 +1,24 @@
from ophyd import Component as Cpt
from ophyd import Device, EpicsSignalRO
class SLSOperatorMessages(Device):
message1 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-MSG1", auto_monitor=True)
message_date1 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-DATE1", auto_monitor=True)
message2 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-MSG2", auto_monitor=True)
message_date2 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-DATE2", auto_monitor=True)
message3 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-MSG3", auto_monitor=True)
message_date3 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-DATE3", auto_monitor=True)
message4 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-MSG4", auto_monitor=True)
message_date4 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-DATE4", auto_monitor=True)
message5 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-MSG5", auto_monitor=True)
message_date5 = Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-DATE5", auto_monitor=True)
# class SLSOperatorMessages(Device):
# pass
# for i in range(5):
# setattr(SLSOperatorMessages, f"message{i}", Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-MSG{i}", auto_monitor=True))
# setattr(SLSOperatorMessages, f"message_date{i}", Cpt(EpicsSignalRO, f"ACOAU-ACCU:OP-DATE{i}", auto_monitor=True))

View File

@ -0,0 +1,2 @@
from .smaract_ophyd import SmaractMotor
from .smaract_controller import SmaractController

View File

@ -0,0 +1,45 @@
import json
from ophyd import Component as Cpt
from ophyd import Device, PositionerBase, Signal
from ophyd.ophydobj import OphydObject
from ophyd_devices.utils.socket import SocketMock
def get_user_functions(obj) -> list:
exclude_list = ["log", "SUB_CONNECTION_CHANGE"]
exclude_classes = [Device, OphydObject, PositionerBase, Signal, Cpt]
for cls in exclude_classes:
exclude_list.extend(dir(cls))
access_list = [
func for func in dir(obj) if not func.startswith("_") and func not in exclude_list
]
return access_list
def is_serializable(f) -> bool:
try:
json.dumps(f)
return True
except (TypeError, OverflowError):
return False
def get_user_interface(obj, obj_interface):
# user_funcs = get_user_functions(obj)
for f in [f for f in dir(obj) if f in obj.USER_ACCESS]:
if f == "controller" or f == "on":
print(f)
m = getattr(obj, f)
if not callable(m):
if is_serializable(m):
obj_interface[f] = {"type": type(m).__name__}
elif isinstance(m, SocketMock):
pass
else:
obj_interface[f] = get_user_interface(m, {})
else:
obj_interface[f] = {"type": "func"}
return obj_interface

View File

@ -0,0 +1,524 @@
import enum
import functools
import json
import logging
import os
import numpy as np
from ophyd_devices.smaract.smaract_errors import (
SmaractCommunicationError,
SmaractErrorCode,
)
from ophyd_devices.utils.controller import Controller
from typeguard import typechecked
logger = logging.getLogger("smaract_controller")
class SmaractCommunicationMode(enum.Enum):
SYNC = 0
ASYNC = 1
def axis_checked(fcn):
"""Decorator to catch attempted access to channels that are not available."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
self._check_axis_number(args[0])
return fcn(self, *args, **kwargs)
return wrapper
def retry_once(fcn):
"""Decorator to rerun a function in case a SmaractCommunicationError was raised. This may happen if the buffer was not empty."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
try:
val = fcn(self, *args, **kwargs)
except (SmaractCommunicationError, SmaractErrorCode):
val = fcn(self, *args, **kwargs)
return val
return wrapper
class SmaractChannelStatus(enum.Enum):
STOPPED = 0
STEPPING = 1
SCANNING = 2
HOLDING = 3
TARGETING = 4
MOVE_DELAY = 5
CALIBRATING = 6
FINDING_REFERENCE_MARK = 7
LOCKED = 9
class SmaractSensorDefinition:
def __init__(self, symbol, type_code, positioner_series, comment, reference_type) -> None:
self.symbol = symbol
self.type_code = type_code
self.comment = comment
self.positioner_series = positioner_series
self.reference_type = reference_type
class SmaractSensors:
smaract_sensor_definition_file = os.path.join(
os.path.dirname(os.path.abspath(__file__)), "smaract_sensors.json"
)
def __init__(self) -> None:
self.avail_sensors = {}
with open(self.smaract_sensor_definition_file) as json_file:
sensor_list = json.load(json_file)
for sensor in sensor_list:
self.avail_sensors[sensor["type_code"]] = SmaractSensorDefinition(**sensor)
class SmaractController(Controller):
USER_ACCESS = [
"socket_put_and_receive",
"smaract_show_all",
"move_open_loop_steps"
]
def __init__(
self,
*,
name="SmaractController",
kind=None,
parent=None,
socket=None,
attr_name="",
labels=None,
):
if not hasattr(self, "_initialized") or not self._initialized:
self._Smaract_axis_per_controller = 6
self._axis = [None for axis_num in range(self._Smaract_axis_per_controller)]
super().__init__(
name=name,
socket=socket,
attr_name=attr_name,
parent=parent,
labels=labels,
kind=kind,
)
self._sensors = SmaractSensors()
def on(self, controller_num=0):
"""Open a new socket connection to the controller"""
if not self.connected:
self.sock.open()
self.connected = True
else:
logger.info("The connection has already been established.")
# warnings.warn(f"The connection has already been established.", stacklevel=2)
def off(self):
"""Close the socket connection to the controller"""
if self.connected:
self.sock.close()
self.connected = False
else:
logger.info("The connection is already closed.")
@axis_checked
def set_axis(self, axis_nr, axis):
self._axis[axis_nr] = axis
def socket_put(self, val: str):
self.sock.put(f":{val}\n".encode())
def socket_get(self):
return self.sock.receive().decode()
def socket_put_and_receive(
self,
val: str,
remove_trailing_chars=True,
check_for_errors=True,
raise_if_not_status=False,
) -> str:
self.socket_put(val)
return_val = self.socket_get()
if remove_trailing_chars:
return_val = self._remove_trailing_characters(return_val)
logger.debug(f"Sending {val}; Returned {return_val}")
if check_for_errors:
self._check_for_error(return_val, raise_if_not_status=raise_if_not_status)
return return_val
@retry_once
@axis_checked
def get_status(self, axis_Id_numeric: int) -> SmaractChannelStatus:
"""Returns the current movement status code of a positioner or end effector.This command can be used to check whether a previously issued movement command has been completed.
Args:
axis_Id_numeric (int): Axis number
Returns:
SmaractChannelStatus: Channel status
"""
return_val = self.socket_put_and_receive(f"GS{axis_Id_numeric}")
if self._message_starts_with(return_val, f":S{axis_Id_numeric}"):
return SmaractChannelStatus(int(return_val.split(",")[1]))
@retry_once
@axis_checked
def is_axis_moving(self, axis_Id_numeric: int) -> bool:
"""Check if axis is moving. Returns true upon open loop move, scanning, closed loop move or reference mark search.
Args:
axis_Id_numeric (int): Axis number.
Returns:
bool: True if axis is moving.
"""
axis_status = self.get_status(axis_Id_numeric)
return axis_status in [
SmaractChannelStatus.STEPPING,
SmaractChannelStatus.SCANNING,
SmaractChannelStatus.TARGETING,
SmaractChannelStatus.FINDING_REFERENCE_MARK,
]
@retry_once
def stop_all_axes(self):
return [
self.socket_put_and_receive(f"S{ax.axis_Id_numeric}", raise_if_not_status=True)
for ax in self._axis
if ax is not None
]
@retry_once
@axis_checked
def axis_is_referenced(self, axis_Id_numeric: int) -> bool:
return_val = self.socket_put_and_receive(f"GPPK{axis_Id_numeric}")
if self._message_starts_with(return_val, f":PPK{axis_Id_numeric}"):
return bool(int(return_val.split(",")[1]))
def all_axes_referenced(self) -> bool:
return all([self.is_axis_referenced(ax) for ax in self._axis if ax is not None])
@retry_once
@axis_checked
def get_position(self, axis_Id_numeric: int) -> float:
"""Returns the current position of a positioner.
Args:
axis_Id_numeric (int): Axis number.
Returns:
float: Position in mm
"""
return_val = self.socket_put_and_receive(f"GP{axis_Id_numeric}")
if self._message_starts_with(return_val, f":P{axis_Id_numeric}"):
return float(return_val.split(",")[1]) / 1e6
@retry_once
@axis_checked
@typechecked
def move_axis_to_absolute_position(
self, axis_Id_numeric: int, target_val: float, hold_time: int = 1000
) -> None:
"""Instructs a positioner to move to a specific position.
Args:
axis_Id_numeric (int): Axis number.
target_val (float): Target position in mm.
hold_time (int, optional): Specifies how long (in milliseconds) the position is actively held after reaching the target. The valid range is 0..60,000. A 0 deactivates this feature, a value of 60,000 is infinite (until manually stopped, see S command). Defaults to 1000.
"""
self.socket_put_and_receive(
f"MPA{axis_Id_numeric},{int(np.round(target_val*1e6))},{hold_time}",
raise_if_not_status=True,
)
@retry_once
@axis_checked
@typechecked
def move_axis_to_relative_position(
self, axis_Id_numeric: int, target_val: float, hold_time: int = 1000
) -> None:
"""Instructs a positioner to move to a position relative to its current position.
Args:
axis_Id_numeric (int): Axis number.
target_val (float): Relative position to move to in mm.
hold_time (int, optional): Specifies how long (in milliseconds) the position is actively held after reaching the target. The valid range is 0..60,000. A 0 deactivates this feature, a value of 60,000 is infinite (until manually stopped, see S command). Defaults to 1000.
"""
self.socket_put_and_receive(
f"MPR{axis_Id_numeric},{int(np.round(target_val*1e6))},{hold_time}",
raise_if_not_status=True,
)
@retry_once
@axis_checked
@typechecked
def move_open_loop_steps(
self, axis_Id_numeric: int, steps: int, amplitude: int=2000, frequency:int=500
) -> None:
"""Move open loop steps
Args:
axis_Id_numeric (int): Axis number.
steps (float): Relative position to move to in mm.
hold_time (int, optional): Specifies how long (in milliseconds) the position is actively held after reaching the target. The valid range is 0..60,000. A 0 deactivates this feature, a value of 60,000 is infinite (until manually stopped, see S command). Defaults to 1000.
"""
self.socket_put_and_receive(
f"MST{axis_Id_numeric},{steps},{amplitude},{frequency}",
raise_if_not_status=True,
)
@retry_once
def get_communication_mode(self) -> SmaractCommunicationMode:
return_val = self.socket_put_and_receive("GCM")
if self._message_starts_with(return_val, f":CM"):
return SmaractCommunicationMode(int(return_val.strip(":CM")))
@retry_once
@axis_checked
def get_channel_type(self, axis_Id_numeric) -> str:
return_val = self.socket_put_and_receive(f"GCT{axis_Id_numeric}")
if self._message_starts_with(return_val, f":CT{axis_Id_numeric}"):
return return_val.split(",")[1]
@retry_once
def get_interface_version(self) -> str:
"""This command may be used to retrieve the interface version of the system. It is useful to check if changes
have been made to the software interface. An application may check the version in order to ensure that the
system behaves as the application expects it to do.
Returns:
str: interface version
"""
return_val = self.socket_put_and_receive("GIV")
if self._message_starts_with(return_val, f":IV"):
return return_val.strip(":IV")
@retry_once
def get_number_of_channels(self) -> int:
"""This command may be used to determine how many control channels are available on a system. This
includes positioner channels and end effector channels. Each channel is of a specific type. Use the GCT
command to determine the types of the channels.
Note that the number of channels does not represent the number positioners and/or end effectors that are
currently connected to the system.
The channel indexes throughout the interface are zero based. If your system has N channels then the valid
range for a channel index is 0.. N-1.
Returns:
int: number of channels
"""
return_val = self.socket_put_and_receive("GNC")
if self._message_starts_with(return_val, f":N"):
return int(return_val.strip(":N"))
@retry_once
def get_system_id(self) -> str:
"""This command may be used to physically identify a system connected to the PC. Each system has a unique
ID which makes it possible to distinguish one from another.
The ID returned is a generic decimal number that uniquely identifies the system.
"""
return_val = self.socket_put_and_receive("GSI")
if self._message_starts_with(return_val, f":ID"):
return return_val.strip(":ID")
@retry_once
def reset(self) -> None:
"""When this command is sent the system will perform a reset. It has the same effect as a power down/power
up cycle. The system replies with an acknowledge string before resetting itself.
"""
self.socket_put_and_receive("R", raise_if_not_status=True)
@retry_once
def set_hcm_mode(self, mode: int):
"""If a Hand Control Module (HCM) is connected to the system, this command may be used to enable or
disable it in order to avoid interference while the software is in control of the system. There are three possible
modes to set:
0: In this mode the Hand Control Module is disabled. It may not be used to control positioners.
1: This is the default setting where the Hand Control Module may be used to control the positioners.
2: In this mode the Hand Control Module cannot be used to control the positioners. However, if there
are positioners with sensors attached, their position data will still be displayed.
Args:
mode (int): HCM mode
"""
if mode not in range(3):
raise ValueError(f"HCM mode must be 0, 1 or 2. Received: {mode}.")
self.socket_put_and_receive(f"SHE{mode}", raise_if_not_status=True)
@retry_once
@axis_checked
def get_position_limits(self, axis_Id_numeric: int) -> list:
"""May be used to read out the travel range limit that is currently
configured for a linear channel.
Args:
axis_Id_numeric (int): Axis
Returns:
list: [low_limit, high_limit] in mm
"""
return_val = self.socket_put_and_receive(f"GPL{axis_Id_numeric}")
if self._message_starts_with(return_val, f":GPL{axis_Id_numeric}"):
return [
float(limit) / 1e6
for limit in return_val.strip(f":GPL{axis_Id_numeric},").split(",")
]
@retry_once
@axis_checked
def set_position_limits(
self, axis_Id_numeric: int, low_limit: float, high_limit: float
) -> None:
"""For positioners with integrated sensors this command may be used to limit the travel range of a linear
positioner by software. By default there is no limit set. If defined the
positioner will not move beyond the limit. This affects open-loop as well as closed-loop movements.
Args:
axis_Id_numeric (int): Axis
low_limit (float): low limit in mm
high_limit (float): high limit in mm
"""
self.socket_put_and_receive(
f"SPL{axis_Id_numeric},{np.round(low_limit*1e6)},{np.round(high_limit*1e6)}",
raise_if_not_status=True,
)
@retry_once
@axis_checked
def get_sensor_type(self, axis_Id_numeric: int) -> SmaractSensorDefinition:
return_val = self.socket_put_and_receive(f"GST{axis_Id_numeric}")
if self._message_starts_with(return_val, f":ST{axis_Id_numeric}"):
return self._sensors.avail_sensors.get(int(return_val.strip(f":ST{axis_Id_numeric},")))
@retry_once
@axis_checked
def set_closed_loop_move_speed(self, axis_Id_numeric: int, move_speed: float) -> None:
"""This command configures the speed control feature of a channel for closed-loop commands move_axis_to_absolute_position. By default the speed control is inactive. In this state the behavior of closed-loop commands is influenced by the maximum driving frequency. If a movement speed is configured, all following closed-loop commands will be executed with the new speed.
Args:
axis_Id_numeric (int): Axis number.
move_speed (float): Movement speed given in mm/s for linear positioners. The valid range is 0 .. 100. A value of 0 (default) deactivates the speed control feature.
"""
move_speed_in_nm_per_s = int(round(move_speed * 1e6))
if move_speed_in_nm_per_s > 100e6 or move_speed_in_nm_per_s < 0:
raise ValueError("Move speed must be within 0 to 100 mm/s.")
self.socket_put_and_receive(
f"SCLS{axis_Id_numeric},{move_speed_in_nm_per_s}", raise_if_not_status=True
)
@retry_once
@axis_checked
def get_closed_loop_move_speed(self, axis_Id_numeric: int) -> float:
"""Returns the currently configured movement speed that is used for closed-loop commands for a channel.
Args:
axis_Id_numeric (int): Axis number.
Returns:
float: move speed in mm/s. A return value of 0 means that the speed control feature is disabled.
"""
return_val = self.socket_put_and_receive(f"GCLS{axis_Id_numeric}")
if self._message_starts_with(return_val, f":CLS{axis_Id_numeric}"):
return float(return_val.strip(f":CLS{axis_Id_numeric},")) * 1e6
def describe(self) -> None:
t = PrettyTable()
t.title = f"{self.__class__.__name__} on {self.sock.host}:{self.sock.port}"
t.field_names = [
"Axis",
"Name",
"Connected",
"Referenced",
"Closed Loop Speed",
"Position",
]
for ax in range(self._Smaract_axis_per_controller):
axis = self._axis[ax]
if axis is not None:
t.add_row(
[
f"{axis.axis_Id_numeric}/{axis.axis_Id}",
axis.name,
axis.connected,
self.axis_is_referenced(axis.axis_Id_numeric),
self.get_closed_loop_move_speed(axis.axis_Id),
axis.readback.read().get(axis.name).get("value"),
]
)
else:
t.add_row([None for t in t.field_names])
print(t)
def _check_axis_number(self, axis_Id_numeric: int) -> None:
if axis_Id_numeric >= self._Smaract_axis_per_controller:
raise ValueError(
f"Axis {axis_Id_numeric} exceeds the available number of axes ({self._Smaract_axis_per_controller})"
)
@axis_checked
def _error_str(self, axis_Id_numeric: int, error_number: int):
return f":E{axis_Id_numeric},{error_number}"
def _get_error_code_from_msg(self, msg: str) -> int:
if msg.startswith(":E"):
return int(msg.split(",")[-1])
else:
return -1
def _get_axis_from_error_code(self, msg: str) -> int:
if msg.startswith(":E"):
try:
return int(msg.strip(":E").split(",")[0])
except ValueError:
return None
else:
return None
def _check_for_error(self, msg: str, axis_Id_numeric: int = None, raise_if_not_status=False):
if msg.startswith(":E"):
if axis_Id_numeric is None:
axis_Id_numeric = self._get_axis_from_error_code(msg)
if axis_Id_numeric is None:
raise SmaractCommunicationError(
"Could not retrieve axis number from error message."
)
if msg != self._error_str(axis_Id_numeric, 0):
error_code = self._get_error_code_from_msg(msg)
if error_code != 0:
raise SmaractErrorCode(error_code)
else:
if raise_if_not_status:
raise SmaractCommunicationError(
"Expected error / status message but failed to parse it."
)
def _remove_trailing_characters(self, var: str) -> str:
if len(var) > 1:
return var.split("\n")[0]
return var
def _message_starts_with(self, msg: str, leading_chars: str) -> bool:
if msg.startswith(leading_chars):
return True
else:
raise SmaractCommunicationError(
f"Expected to receive a return message starting with {leading_chars} but instead received '{msg}'"
)

View File

@ -0,0 +1,47 @@
SMARACT_ERRORS = {
1: "Syntax Error: The command could not be processed due to a syntactical error.",
2: "Invalid Command Error: The command given is not known to the system.",
3: "Overflow Error: This error occurs if a parameter given is too large and therefore cannot be processed.",
4: "Parse Error: The command could not be processed due to a parse error.",
5: "Too Few Parameters Error: The specified command requires more parameters in order to be executed.",
6: "Too Many Parameters Error: There were too many parameters given for the specified command.",
7: "Invalid Parameter Error: A parameter given exceeds the valid range. Please see the command description for valid ranges of the parameters.",
8: "Wrong Mode Error: This error is generated if the specified command is not available in the current communication mode. For example, the SRC command is not executable in synchronous mode.",
129: "No Sensor Present Error: This error occurs if a command was given that requires sensor feedback, but the addressed positioner has none attached.",
140: "Sensor Disabled Error: This error occurs if a command was given that requires sensor feedback, but the sensor of the addressed positioner is disabled (see SSE command).",
141: "Command Overridden Error: This error is only generated in the asynchronous communication mode. When the software commands a movement which is then interrupted by the Hand Control Module, an error of this type is generated.",
142: "End Stop Reached Error: This error is generated in asynchronous mode if the target position of a closed-loop command could not be reached, because a mechanical end stop was detected. After this error the positioner will have a movement status code of 0 (stopped).",
143: "Wrong Sensor Type Error: This error occurs if a closed-loop command does not match the sensor type that is currently configured for the addressed channel. For example, issuing a GP command while the targeted channel is configured as rotary will lead to this error.",
144: "Could Not Find Reference Mark Error: This error is generated in asynchronous mode (see SCM) if the search for a reference mark was aborted.",
145: "Wrong End Effector Type Error: This error occurs if a command does not match the end effector type that is currently configured for the addressed channel. For example, sending GF while the targeted channel is configured for a gripper will lead to this error.",
146: "Movement Locked Error: This error occurs if a movement command is issued while the system is in the locked state. ",
147: "Range Limit Reached Error: If a range limit is defined (SPL or SAL) and the positioner is about to move beyond this limit, then the positioner will stop and report this error (only in asynchronous mode, see SCM). After this error the positioner will have status code of 0 (stopped).",
148: "Physical Position Unknown Error: A range limit is only allowed to be defined if the positioner “knows” its physical position. If this is not the case, the commands SPL and SAL will return this error code.",
150: "Command Not Processable Error: This error is generated if a command is sent to a channel when it is in a state where the command cannot be processed. For example, to change the sensor type of a channel the addressed channel must be completely stopped. In this case send a stop command before changing the type.",
151: "Waiting For Trigger Error: If there is at least one command queued in the command queue then you may only append more commands (if the queue is not full), but you may not issue movement commands for immediate execution. Doing so will generate this error. See section 2.4.5 “Command Queues“.",
152: "Command Not Triggerable Error: After sending a ATC command you are required to issue a movement command that is to be triggered by the given event source. Commands that cannot be triggered will generate this error.",
153: "Command Queue Full Error: This error is generated if you attempt to append more commands to the command queue, but the queue cannot hold anymore commands. The queue capacity may be read out with a get channel property command (GCP on p.30).",
154: "Invalid Component Error: Indicates that a component (e.g. SCP) was selected that does not exist.",
155: "Invalid Sub Component Error: Indicates that a sub component (e.g. SCP) was selected that does not exist.",
156: "Invalid Property Error: Indicates that a property (e.g. SCP) was selected that does not exist.",
157: "Permission Denied Error: This error is generated when you call a functionality which is not unlocked for the system (e.g. Low Vibration Mode).",
}
class SmaractError(Exception):
pass
class SmaractCommunicationError(SmaractError):
pass
class SmaractErrorCode(SmaractError):
def __init__(self, error_code: int, message=""):
self.error_code = error_code
self.error_code_message = SMARACT_ERRORS.get(error_code, "UNKNOWN ERROR")
self.message = message
super().__init__(self.message)
def __str__(self):
return f"{self.error_code} / {self.error_code_message}. {self.message}"

View File

@ -0,0 +1,309 @@
import logging
import threading
import time
from typing import List
import numpy as np
from ophyd import Component as Cpt
from ophyd import Device, PositionerBase
from ophyd.status import wait as status_wait
from ophyd.utils import ReadOnlyError
from ophyd_devices.smaract.smaract_controller import SmaractController
from ophyd_devices.smaract.smaract_errors import SmaractCommunicationError, SmaractError
from ophyd_devices.utils.socket import SocketIO, SocketSignal, raise_if_disconnected
logger = logging.getLogger("smaract")
class SmaractSignalBase(SocketSignal):
def __init__(self, signal_name, **kwargs):
self.signal_name = signal_name
super().__init__(**kwargs)
self.controller = self.parent.controller
self.sock = self.parent.controller.sock
class SmaractSignalRO(SmaractSignalBase):
def __init__(self, signal_name, **kwargs):
super().__init__(signal_name, **kwargs)
self._metadata["write_access"] = False
def _socket_set(self, val):
raise ReadOnlyError("Read-only signals cannot be set")
class SmaractReadbackSignal(SmaractSignalRO):
def _socket_get(self):
return self.controller.get_position(self.parent.axis_Id_numeric)
class SmaractSetpointSignal(SmaractSignalBase):
setpoint = 0
def _socket_get(self):
return self.setpoint
def _socket_set(self, val):
target_val = val * self.parent.sign
self.setpoint = target_val
if self.controller.axis_is_referenced(self.parent.axis_Id_numeric):
self.controller.move_axis_to_absolute_position(self.parent.axis_Id_numeric, target_val)
# parameters are axis_no,pos_mm*1e6, hold_time_sec*1e3
else:
raise SmaractError(f"Axis {self.parent.axis_Id_numeric} is not referenced.")
class SmaractMotorIsMoving(SmaractSignalRO):
def _socket_get(self):
return self.controller.is_axis_moving(self.parent.axis_Id_numeric)
class SmaractAxisReferenced(SmaractSignalRO):
def _socket_get(self):
return self.parent.controller.axis_is_referenced(self.parent.axis_Id_numeric)
class SmaractAxisLimits(SmaractSignalBase):
def _socket_get(self):
limits_msg = self.controller.socket_put_and_receive(f"GPL{self.parent.axis_Id_numeric}")
if limits_msg.startswith(":PL"):
limits = [
float(limit)
for limit in limits_msg.strip(f":PL{self.parent.axis_Id_numeric},").split(",")
]
else:
raise SmaractCommunicationError("Expected to receive message starting with :PL.")
return limits
# def _socket_set(self, val):
class SmaractMotor(Device, PositionerBase):
USER_ACCESS = ["controller"]
readback = Cpt(
SmaractReadbackSignal,
signal_name="readback",
kind="hinted",
)
user_setpoint = Cpt(SmaractSetpointSignal, signal_name="setpoint")
# motor_resolution = Cpt(
# SmaractMotorResolution, signal_name="resolution", kind="config"
# )
motor_is_moving = Cpt(SmaractMotorIsMoving, signal_name="motor_is_moving", kind="normal")
# all_axes_referenced = Cpt(
# SmaractAxesReferenced, signal_name="all_axes_referenced", kind="config"
# )
SUB_READBACK = "readback"
SUB_CONNECTION_CHANGE = "connection_change"
_default_sub = SUB_READBACK
def __init__(
self,
axis_Id,
prefix="",
*,
name,
kind=None,
read_attrs=None,
configuration_attrs=None,
parent=None,
host="mpc2680.psi.ch",
port=8085,
sign=1,
socket_cls=SocketIO,
**kwargs,
):
self.axis_Id = axis_Id
self.sign = sign
self.controller = SmaractController(socket=socket_cls(host=host, port=port))
self.controller.set_axis(self.axis_Id_numeric, axis=self)
self.tolerance = kwargs.pop("tolerance", 0.5)
super().__init__(
prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
**kwargs,
)
self.readback.name = self.name
self.controller.subscribe(
self._update_connection_state, event_type=self.SUB_CONNECTION_CHANGE
)
self._update_connection_state()
def _update_connection_state(self, **kwargs):
for walk in self.walk_signals():
walk.item._metadata["connected"] = self.controller.connected
@raise_if_disconnected
def move(self, position, wait=True, **kwargs):
"""Move to a specified position, optionally waiting for motion to
complete.
Parameters
----------
position
Position to move to
moved_cb : callable
Call this callback when movement has finished. This callback must
accept one keyword argument: 'obj' which will be set to this
positioner instance.
timeout : float, optional
Maximum time to wait for the motion. If None, the default timeout
for this positioner is used.
Returns
-------
status : MoveStatus
Raises
------
TimeoutError
When motion takes longer than `timeout`
ValueError
On invalid positions
RuntimeError
If motion fails other than timing out
"""
self._started_moving = False
timeout = kwargs.pop("timeout", 4)
status = super().move(position, timeout=timeout, **kwargs)
self.user_setpoint.put(position, wait=False)
def move_and_finish():
while self.motor_is_moving.get():
val = self.readback.read()
self._run_subs(
sub_type=self.SUB_READBACK,
value=val,
timestamp=time.time(),
)
time.sleep(0.1)
val = self.readback.read()
success = np.isclose(
val[self.name]["value"],
position,
atol=self.tolerance,
)
self._done_moving(success=success)
threading.Thread(target=move_and_finish, daemon=True).start()
try:
if wait:
status_wait(status)
except KeyboardInterrupt:
self.stop()
raise
return status
@property
def axis_Id(self):
return self._axis_Id_alpha
@axis_Id.setter
def axis_Id(self, val):
if isinstance(val, str):
if len(val) != 1:
raise ValueError(f"Only single-character axis_Ids are supported.")
self._axis_Id_alpha = val
self._axis_Id_numeric = ord(val.lower()) - 97
else:
raise TypeError(f"Expected value of type str but received {type(val)}")
@property
def axis_Id_numeric(self):
return self._axis_Id_numeric
@axis_Id_numeric.setter
def axis_Id_numeric(self, val):
if isinstance(val, int):
if val > 26:
raise ValueError(f"Numeric value exceeds supported range.")
self._axis_Id_alpha = val
self._axis_Id_numeric = (chr(val + 97)).capitalize()
else:
raise TypeError(f"Expected value of type int but received {type(val)}")
@property
def egu(self):
"""The engineering units (EGU) for positions"""
return "mm"
def stage(self) -> List[object]:
self.controller.on()
return super().stage()
def unstage(self) -> List[object]:
self.controller.off()
return super().unstage()
def stop(self, *, success=False):
self.controller.stop_all_axes()
return super().stop(success=success)
if __name__ == "__main__":
logging.basicConfig(level=logging.DEBUG)
mock = False
if not mock:
lsmarA = SmaractMotor("A", name="lsmarA", host="mpc2680.psi.ch", port=8085, sign=1)
lsmarB = SmaractMotor("B", name="lsmarB", host="mpc2680.psi.ch", port=8085, sign=1)
lsmarA.stage()
lsmarB.stage()
# status = leyey.move(2, wait=True)
# status = leyey.move(2, wait=True)
lsmarA.read()
lsmarB.read()
lsmarA.get()
lsmarB.get()
lsmarA.describe()
lsmarA.unstage()
lsmarA.controller.off()
# status = leyey.move(10, wait=False)
# print(lSmaract_controller)
else:
from ophyd_devices.utils.socket import SocketMock
lsmarA = SmaractMotor(
"A",
name="lsmarA",
host="mpc2680.psi.ch",
port=8085,
sign=1,
socket_cls=SocketMock,
)
lsmarB = SmaractMotor(
"B",
name="lsmarB",
host="mpc2680.psi.ch",
port=8085,
sign=1,
socket_cls=SocketMock,
)
lsmarA.stage()
lsmarB.stage()
lsmarA.read()
lsmarB.read()
lsmarA.get()
lsmarB.get()
lsmarA.describe()
lsmarA.unstage()
lsmarA.controller.off()
# status = leyey.move(10, wait=False)
# print(lSmaract_controller)

View File

@ -0,0 +1,303 @@
[
{
"symbol": "S",
"type_code": 1,
"positioner_series": "SLCxxxxs",
"comment": "linear positioner with nano sensor",
"reference_type": "mark"
},
{
"symbol": "SR",
"type_code": 2,
"positioner_series": "SR36xxs, SR3511s, SR5714s, SR7021s, SR2812s, SR7012s, SR4513s, SR5018s",
"comment": "rotary positioner with nano sensor",
"reference_type": "mark"
},
{
"symbol": "SP",
"type_code": 5,
"positioner_series": "SLCxxxxrs",
"comment": "linear positioner with nano sensor, large actuator",
"reference_type": "mark"
},
{
"symbol": "SC",
"type_code": 6,
"positioner_series": "SLCxxxxsc",
"comment": "linear positioner with nano sensor, distance coded reference marks",
"reference_type": "mark*"
},
{
"symbol": "SR20",
"type_code": 8,
"positioner_series": "SR2013s, SR1612s",
"comment": "rotary positioner with nano sensor",
"reference_type": "mark"
},
{
"symbol": "M",
"type_code": 9,
"positioner_series": "SLCxxxxm",
"comment": "linear positioner with micro sensor",
"reference_type": "end stop"
},
{
"symbol": "GD",
"type_code": 11,
"positioner_series": "SGO60.5m",
"comment": "goniometer with micro sensor (60.5mm radius)",
"reference_type": "end stop"
},
{
"symbol": "GE",
"type_code": 12,
"positioner_series": "SGO77.5m",
"comment": "goniometer with micro sensor (77.5mm radius)",
"reference_type": "end stop"
},
{
"symbol": "GF",
"type_code": 14,
"positioner_series": "SR1209m",
"comment": "rotary positioner with micro sensor",
"reference_type": "end stop"
},
{
"symbol": "G605S",
"type_code": 16,
"positioner_series": "SGO60.5s",
"comment": "goniometer with nano sensor (60.5mm radius)",
"reference_type": "mark"
},
{
"symbol": "G775S",
"type_code": 17,
"positioner_series": "SGO77.5s",
"comment": "goniometer with nano sensor (77.5mm radius)",
"reference_type": "mark"
},
{
"symbol": "SC500",
"type_code": 18,
"positioner_series": "SLLxxsc",
"comment": "linear positioner with nano sensor, distance coded reference marks",
"reference_type": "mark*"
},
{
"symbol": "G955S",
"type_code": 19,
"positioner_series": "SGO95.5s",
"comment": "goniometer with nano sensor (95.5mm radius)",
"reference_type": "mark"
},
{
"symbol": "SR77",
"type_code": 20,
"positioner_series": "SR77xxs",
"comment": "rotary positioner with nano sensor",
"reference_type": "mark"
},
{
"symbol": "SD",
"type_code": 21,
"positioner_series": "SLCxxxxds, SLLxxs",
"comment": "like S, but with extended scanning Range",
"reference_type": "mark"
},
{
"symbol": "R20ME",
"type_code": 22,
"positioner_series": "SR2013sx, SR1410sx",
"comment": "rotary positioner with MicroE sensor",
"reference_type": "mark"
},
{
"symbol": "SR2",
"type_code": 23,
"positioner_series": "SR36xxs, SR3511s, SR5714s, SR7021s, SR2812s",
"comment": "like SR, for high applied masses",
"reference_type": "mark"
},
{
"symbol": "SCD",
"type_code": 24,
"positioner_series": "SLCxxxxdsc",
"comment": "like SP, but with distance coded reference marks",
"reference_type": "mark*"
},
{
"symbol": "SRC",
"type_code": 25,
"positioner_series": "SR7021sc",
"comment": "like SR, but with distance coded reference marks",
"reference_type": "mark*"
},
{
"symbol": "SR36M",
"type_code": 26,
"positioner_series": "SR3610m",
"comment": "rotary positioner, no end stops",
"reference_type": "none"
},
{
"symbol": "SR36ME",
"type_code": 27,
"positioner_series": "SR3610m",
"comment": "rotary positioner with end stops",
"reference_type": "end stop"
},
{
"symbol": "SR50M",
"type_code": 28,
"positioner_series": "SR5018m",
"comment": "rotary positioner, no end stops",
"reference_type": "none"
},
{
"symbol": "SR50ME",
"type_code": 29,
"positioner_series": "SR5018m",
"comment": "rotary positioner with end stops",
"reference_type": "end stop"
},
{
"symbol": "G1045S",
"type_code": 30,
"positioner_series": "SGO104.5s",
"comment": "goniometer with nano sensor (104.5mm radius)",
"reference_type": "mark"
},
{
"symbol": "G1395S",
"type_code": 31,
"positioner_series": "SGO139.5s",
"comment": "goniometer with nano sensor (139.5mm radius)",
"reference_type": "mark"
},
{
"symbol": "MD",
"type_code": 32,
"positioner_series": "SLCxxxxdme",
"comment": "like M, but with large actuator",
"reference_type": "end stop"
},
{
"symbol": "G935M",
"type_code": 33,
"positioner_series": "SGO93.5me",
"comment": "goniometer with micro sensor (93.5mm radius)",
"reference_type": "end stop"
},
{
"symbol": "SHL20",
"type_code": 34,
"positioner_series": "SHL-20",
"comment": "high load vertical positioner",
"reference_type": "mark"
},
{
"symbol": "SCT",
"type_code": 35,
"positioner_series": "SLCxxxxscu",
"comment": "like SCD, but with even larger actuator",
"reference_type": "mark*"
},
{
"symbol": "SR77T",
"type_code": 36,
"positioner_series": "SR7021s",
"comment": "like SR77, but with larger actuator",
"reference_type": "mark"
},
{
"symbol": "SR120",
"type_code": 37,
"positioner_series": "SR120xxs",
"comment": "large rotary positioner",
"reference_type": "mark"
},
{
"symbol": "LC",
"type_code": 38,
"positioner_series": "SLCxxxxl",
"comment": "linear positioner with improved micro sensor",
"reference_type": "mark*"
},
{
"symbol": "LR",
"type_code": 39,
"positioner_series": "SRxxxxl",
"comment": "rotary positioner with improved micro sensor",
"reference_type": "mark"
},
{
"symbol": "LCD",
"type_code": 40,
"positioner_series": "SLCxxxxdl",
"comment": "like LC, but with large actuator",
"reference_type": "mark*"
},
{
"symbol": "L",
"type_code": 41,
"positioner_series": "SLCxxxxl",
"comment": "linear positioner with improved micro sensor",
"reference_type": "mark"
},
{
"symbol": "LD",
"type_code": 42,
"positioner_series": "SLCxxxxdl",
"comment": "like L, but with large actuator",
"reference_type": "mark"
},
{
"symbol": "LE",
"type_code": 43,
"positioner_series": "SLCxxxxl",
"comment": "Linear positioner with improved micro sensor",
"reference_type": "end stop"
},
{
"symbol": "LED",
"type_code": 44,
"positioner_series": "SLCxxxxdl",
"comment": "Like L, but with large actuator",
"reference_type": "end stop"
},
{
"symbol": "GDD",
"type_code": 45,
"positioner_series": "SGO60.5md",
"comment": "goniometer with micro sensor (60.5mm radius), large actuator",
"reference_type": "end stop"
},
{
"symbol": "GED",
"type_code": 46,
"positioner_series": "SGO77.5md",
"comment": "goniometer with micro sensor (77.5mm radius), large actuator",
"reference_type": "end stop"
},
{
"symbol": "G935S",
"type_code": 47,
"positioner_series": "SGO96.5s",
"comment": "goniometer with nano sensor (93.5mm radius)",
"reference_type": "mark"
},
{
"symbol": "G605DS",
"type_code": 48,
"positioner_series": "SGO60.5ds",
"comment": "goniometer with nano sensor (60.5mm radius), large actuator",
"reference_type": "mark"
},
{
"symbol": "G775DS",
"type_code": 49,
"positioner_series": "SGO77.5ds",
"comment": "goniometer with nano sensor (77.5mm radius), large actuator",
"reference_type": "mark"
}
]

View File

View File

@ -0,0 +1,110 @@
import functools
import threading
import warnings
from ophyd.ophydobj import OphydObject
from ophyd_devices.utils.socket import SocketIO
def threadlocked(fcn):
"""Ensure that thread acquires and releases the lock."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
with self._lock:
return fcn(self, *args, **kwargs)
return wrapper
class SingletonController:
_controller_instance = None
def __init__(self) -> None:
self._lock = threading.RLock()
def on(self):
pass
def off(self):
pass
def __new__(cls, *args, **kwargs):
if not SingletonController._controller_instance:
SingletonController._controller_instance = object.__new__(cls)
return SingletonController._controller_instance
class Controller(OphydObject):
_controller_instances = {}
SUB_CONNECTION_CHANGE = "connection_change"
def __init__(
self,
*,
name=None,
socket=None,
attr_name="",
parent=None,
labels=None,
kind=None,
):
if not hasattr(self, "_initialized"):
super().__init__(
name=name, attr_name=attr_name, parent=parent, labels=labels, kind=kind
)
self._lock = threading.RLock()
self._initialize(socket)
self._initialized = True
def _initialize(self, socket):
self._connected = False
self._set_default_values()
self.sock = socket if socket is not None else SocketIO()
def _set_default_values(self):
# no. of axes controlled by each controller
self._axis_per_controller = 8
self._motors = [None for axis_num in range(self._axis_per_controller)]
@property
def connected(self):
return self._connected
@connected.setter
def connected(self, value):
self._connected = value
self._run_subs(sub_type=self.SUB_CONNECTION_CHANGE)
def set_motor(self, motor, axis):
"""Set the motor instance for a specified controller axis."""
self._motors[axis] = motor
def get_motor(self, axis):
"""Get motor instance for a specified controller axis."""
return self._motors[axis]
def on(self, controller_num=0):
"""Open a new socket connection to the controller"""
if not self.connected:
self.connected = True
else:
warnings.warn(f"The connection has already been established.", stacklevel=2)
def off(self):
"""Close the socket connection to the controller"""
self.sock.close()
self.connected = False
def __new__(cls, *args, **kwargs):
socket = kwargs.get("socket")
if not hasattr(socket, "host"):
raise RuntimeError("Socket must specify a host.")
if not hasattr(socket, "port"):
raise RuntimeError("Socket must specify a port.")
host_port = f"{socket.host}:{socket.port}"
if host_port not in Controller._controller_instances:
Controller._controller_instances[host_port] = object.__new__(cls)
return Controller._controller_instances[host_port]

View File

@ -0,0 +1,17 @@
from bluesky import RunEngine
from bluesky.plans import grid_scan
from bluesky.callbacks.best_effort import BestEffortCallback
from bluesky.callbacks.mpl_plotting import LivePlot
RE = RunEngine({})
from bluesky.callbacks.best_effort import BestEffortCallback
bec = BestEffortCallback()
# Send all metadata/data captured to the BestEffortCallback.
RE.subscribe(bec)
# RE.subscribe(dummy)
# RE(grid_scan(dets, motor1, -10, 10, 10, motor2, -10, 10, 10))

View File

@ -0,0 +1,264 @@
import abc
import functools
import logging
import socket
import time
import typing
import numpy as np
from ophyd import Signal
from ophyd.utils.errors import DisconnectedError
logger = logging.getLogger("socket")
def raise_if_disconnected(fcn):
"""Decorator to catch attempted access to disconnected Galil channels."""
@functools.wraps(fcn)
def wrapper(self, *args, **kwargs):
if self.connected:
return fcn(self, *args, **kwargs)
else:
raise DisconnectedError("{} is not connected".format(self.name))
return wrapper
DEFAULT_EPICSSIGNAL_VALUE = object()
_type_map = {
"number": (float, np.floating),
"array": (np.ndarray, list, tuple),
"string": (str,),
"integer": (int, np.integer),
}
def data_shape(val):
"""Determine data-shape (dimensions)
Returns
-------
list
Empty list if val is number or string, otherwise
``list(np.ndarray.shape)``
"""
if data_type(val) != "array":
return []
try:
return list(val.shape)
except AttributeError:
return [len(val)]
def data_type(val):
"""Determine the JSON-friendly type name given a value
Returns
-------
str
One of {'number', 'integer', 'array', 'string'}
Raises
------
ValueError if the type is not recognized
"""
bad_iterables = (str, bytes, dict)
if isinstance(val, typing.Iterable) and not isinstance(val, bad_iterables):
return "array"
for json_type, py_types in _type_map.items():
if isinstance(val, py_types):
return json_type
raise ValueError(
f"Cannot determine the appropriate bluesky-friendly data type for "
f"value {val} of Python type {type(val)}. "
f"Supported types include: int, float, str, and iterables such as "
f"list, tuple, np.ndarray, and so on."
)
class SocketSignal(abc.ABC, Signal):
SUB_SETPOINT = "setpoint"
@abc.abstractmethod
def _socket_get(self):
...
@abc.abstractmethod
def _socket_set(self, val):
...
def get(self):
self._readback = self._socket_get()
return self._readback
def put(
self,
value,
force=False,
connection_timeout=1,
callback=None,
use_complete=None,
timeout=1,
**kwargs,
):
"""Using channel access, set the write PV to `value`.
Keyword arguments are passed on to callbacks
Parameters
----------
value : any
The value to set
force : bool, optional
Skip checking the value in Python first
connection_timeout : float, optional
If not already connected, allow up to `connection_timeout` seconds
for the connection to complete.
use_complete : bool, optional
Override put completion settings
callback : callable
Callback for when the put has completed
timeout : float, optional
Timeout before assuming that put has failed. (Only relevant if
put completion is used.)
"""
if not force:
pass
# self.check_value(value)
self.wait_for_connection(timeout=connection_timeout)
if use_complete is None:
use_complete = False
self._socket_set(value)
old_value = self._parent.position
timestamp = time.time()
super().put(value, timestamp=timestamp, force=True)
self._run_subs(
sub_type=self.SUB_SETPOINT,
old_value=old_value,
value=value,
timestamp=timestamp,
)
def describe(self):
"""Provide schema and meta-data for :meth:`~BlueskyInterface.read`
This keys in the `OrderedDict` this method returns must match the
keys in the `OrderedDict` return by :meth:`~BlueskyInterface.read`.
This provides schema related information, (ex shape, dtype), the
source (ex PV name), and if available, units, limits, precision etc.
Returns
-------
data_keys : OrderedDict
The keys must be strings and the values must be dict-like
with the ``event_model.event_descriptor.data_key`` schema.
"""
if self._readback is DEFAULT_EPICSSIGNAL_VALUE:
val = self.get()
else:
val = self._readback
return {
self.name: {
"source": f"{self.parent.controller.name}:{self.name}",
"dtype": data_type(val),
"shape": data_shape(val),
}
}
class SocketIO:
"""SocketIO helper class for TCP IP connections"""
def __init__(self, host, port):
self.host = host
self.port = port
self.is_open = False
self._initialize_socket()
def connect(self):
print(f"connecting to {self.host} port {self.port}")
# self.sock.create_connection((host, port))
if self.sock is None:
self._initialize_socket()
self.sock.connect((self.host, self.port))
def _put(self, msg_bytes):
logger.debug(f"put message: {msg_bytes}")
return self.sock.send(msg_bytes)
def _recv(self, buffer_length=1024):
msg = self.sock.recv(buffer_length)
logger.debug(f"recv message: {msg}")
return msg
def _initialize_socket(self):
self.sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.sock.settimeout(5)
def put(self, msg):
return self._put(msg)
def receive(self, buffer_length=1024):
return self._recv(buffer_length=buffer_length)
def open(self):
self.connect()
self.is_open = True
def close(self):
self.sock.close()
self.sock = None
self.is_open = False
class SocketMock:
def __init__(self, host, port):
self.host = host
self.port = port
self.buffer_put = b""
self.buffer_recv = [b" -12800"]
self.is_open = False
# self.open()
def connect(self):
print(f"connecting to {self.host} port {self.port}")
def _put(self, msg_bytes):
self.buffer_put = msg_bytes
print(self.buffer_put)
def _recv(self, buffer_length=1024):
print(self.buffer_recv)
if isinstance(self.buffer_recv, list):
if len(self.buffer_recv) > 0:
ret_val = self.buffer_recv.pop(0)
else:
ret_val = b""
return ret_val
return self.buffer_recv
def _initialize_socket(self):
pass
def put(self, msg):
return self._put(msg)
def receive(self, buffer_length=1024):
return self._recv(buffer_length=buffer_length)
def open(self):
self._initialize_socket()
self.is_open = True
def close(self):
self.sock = None
self.is_open = False

4
requirements.txt Normal file
View File

@ -0,0 +1,4 @@
ophyd
typeguard
prettytable
pytest

22
setup.cfg Normal file
View File

@ -0,0 +1,22 @@
[metadata]
name = ophyd_devices
version = 0.0.1
description = Custom device implementations based on the ophyd hardware abstraction layer
long_description = file: README.md
long_description_content_type = text/markdown
url = https://github.com/pypa/sampleproject
project_urls =
Bug Tracker = https://github.com/pypa/sampleproject/issues
classifiers =
Programming Language :: Python :: 3
License :: OSI Approved :: MIT License
Operating System :: OS Independent
[options]
package_dir =
= ./
packages = find:
python_requires = >=3.7
[options.packages.find]
where = ./

4
setup.py Normal file
View File

@ -0,0 +1,4 @@
from setuptools import setup
if __name__ == "__main__":
setup(install_requires=["ophyd", "typeguard", "prettytable", "pytest"])

60
tests/test_galil.py Normal file
View File

@ -0,0 +1,60 @@
import pytest
from ophyd_devices.galil.galil_ophyd import GalilMotor
from utils import SocketMock
@pytest.mark.parametrize(
"pos,msg,sign",
[
(1, b" -12800\n\r", 1),
(-1, b" -12800\n\r", -1),
],
)
def test_axis_get(pos, msg, sign):
leyey = GalilMotor(
"H",
name="leyey",
host="mpc2680.psi.ch",
port=8081,
sign=sign,
socket_cls=SocketMock,
)
leyey.controller.sock.flush_buffer()
leyey.stage()
leyey.controller.sock.buffer_recv = msg
val = leyey.read()
assert val["leyey"]["value"] == pos
assert leyey.readback.get() == pos
@pytest.mark.parametrize(
"target_pos,socket_put_messages,socket_get_messages",
[
(
0,
[
b"MG allaxref\r",
b"MG_XQ0\r",
b"naxis=7\r",
b"ntarget=0.000\r",
b"movereq=1\r",
b"XQ#NEWPAR\r",
],
[
b"1.00",
b"-1",
b":",
b":",
b":",
b":",
],
),
],
)
def test_axis_put(target_pos, socket_put_messages, socket_get_messages):
leyey = GalilMotor("H", name="leyey", host="mpc2680.psi.ch", port=8081, socket_cls=SocketMock)
leyey.controller.sock.flush_buffer()
leyey.controller.sock.buffer_recv = socket_get_messages
leyey.user_setpoint.put(target_pos)
assert leyey.controller.sock.buffer_put == socket_put_messages

144
tests/test_npoint_piezo.py Normal file
View File

@ -0,0 +1,144 @@
import pytest
from ophyd_devices.npoint import NPointController, NPointAxis
class SocketMock:
def __init__(self, sock=None):
self.buffer_put = ""
self.buffer_recv = ""
self.is_open = False
if sock is None:
self.open()
else:
self.sock = sock
def connect(self, host, port):
print(f"connecting to {host} port {port}")
# self.sock.create_connection((host, port))
# self.sock.connect((host, port))
def _put(self, msg_bytes):
self.buffer_put = msg_bytes
print(self.buffer_put)
def _recv(self, buffer_length=1024):
print(self.buffer_recv)
return self.buffer_recv
def _initialize_socket(self):
pass
def put(self, msg):
return self._put(msg)
def receive(self, buffer_length=1024):
return self._recv(buffer_length=buffer_length)
def open(self):
self._initialize_socket()
self.is_open = True
def close(self):
self.sock = None
self.is_open = False
@pytest.mark.parametrize(
"pos,msg",
[
(5, b"\xa2\x18\x12\x83\x11\xcd\xcc\x00\x00U"),
(0, b"\xa2\x18\x12\x83\x11\x00\x00\x00\x00U"),
(-5, b"\xa2\x18\x12\x83\x1133\xff\xffU"),
],
)
def test_axis_put(pos, msg):
controller = NPointController(SocketMock())
npointx = NPointAxis(controller, 0, "nx")
controller.on()
npointx.set(pos)
assert npointx.controller.socket.buffer_put == msg
@pytest.mark.parametrize(
"pos, msg_in, msg_out",
[
(5.0, b"\xa04\x13\x83\x11U", b"\xa0\x34\x13\x83\x11\xcd\xcc\x00\x00U"),
(0, b"\xa04\x13\x83\x11U", b"\xa0\x34\x13\x83\x11\x00\x00\x00\x00U"),
(-5, b"\xa04\x13\x83\x11U", b"\xa0\x34\x13\x83\x1133\xff\xffU"),
],
)
def test_axis_get_out(pos, msg_in, msg_out):
controller = NPointController(SocketMock())
npointx = NPointAxis(controller, 0, "nx")
controller.on()
npointx.controller.socket.buffer_recv = msg_out
assert pytest.approx(npointx.get(), rel=0.01) == pos
# assert controller.socket.buffer_put == msg_in
@pytest.mark.parametrize(
"axis, msg_in, msg_out",
[
(0, b"\xa04\x13\x83\x11U", b"\xa0\x34\x13\x83\x11\xcd\xcc\x00\x00U"),
(1, b"\xa04#\x83\x11U", b"\xa0\x34\x13\x83\x11\x00\x00\x00\x00U"),
(2, b"\xa043\x83\x11U", b"\xa0\x34\x13\x83\x1133\xff\xffU"),
],
)
def test_axis_get_in(axis, msg_in, msg_out):
controller = NPointController(SocketMock())
npointx = NPointAxis(controller, 0, "nx")
controller.on()
controller.socket.buffer_recv = msg_out
controller._get_current_pos(axis)
assert controller.socket.buffer_put == msg_in
def test_axis_out_of_range():
controller = NPointController(SocketMock())
with pytest.raises(ValueError):
npointx = NPointAxis(controller, 3, "nx")
def test_get_axis_out_of_range():
controller = NPointController(SocketMock())
with pytest.raises(ValueError):
controller._get_current_pos(3)
def test_set_axis_out_of_range():
controller = NPointController(SocketMock())
with pytest.raises(ValueError):
controller._set_target_pos(3, 5)
@pytest.mark.parametrize(
"in_buffer, byteorder, signed, val",
[
(["0x0", "0x0", "0xcc", "0xcd"], "big", True, 52429),
(["0xcd", "0xcc", "0x0", "0x0"], "little", True, 52429),
(["cd", "cc", "00", "00"], "little", True, 52429),
],
)
def test_hex_list_to_int(in_buffer, byteorder, signed, val):
assert (
NPointController._hex_list_to_int(in_buffer, byteorder=byteorder, signed=signed)
== val
)
@pytest.mark.parametrize(
"axis, msg_in, msg_out",
[
(0, b"\xa0x\x10\x83\x11U", b"\xa0\x78\x13\x83\x11\x64\x00\x00\x00U"),
(1, b"\xa0x \x83\x11U", b"\xa0\x78\x13\x83\x11\x64\x00\x00\x00U"),
(2, b"\xa0x0\x83\x11U", b"\xa0\x78\x13\x83\x11\x64\x00\x00\x00U"),
],
)
def test_get_range(axis, msg_in, msg_out):
controller = NPointController(SocketMock())
npointx = NPointAxis(controller, 0, "nx")
controller.on()
controller.socket.buffer_recv = msg_out
val = controller._get_range(axis)
assert controller.socket.buffer_put == msg_in and val == 100

238
tests/test_smaract.py Normal file
View File

@ -0,0 +1,238 @@
import pytest
from ophyd_devices.smaract import SmaractController
from ophyd_devices.smaract.smaract_controller import SmaractCommunicationMode
from ophyd_devices.smaract.smaract_errors import (
SmaractCommunicationError,
SmaractErrorCode,
)
from ophyd_devices.smaract.smaract_ophyd import SmaractMotor
from utils import SocketMock
@pytest.mark.parametrize(
"axis,position,get_message,return_msg",
[
(0, 50, b":GP0\n", b":P0,50000000"),
(1, 0, b":GP1\n", b":P1,0"),
(0, -50, b":GP0\n", b":P0,-50000000"),
(0, -50.23, b":GP0\n", b":P0,-50230000"),
],
)
def test_get_position(axis, position, get_message, return_msg):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
val = controller.get_position(axis)
assert val == position
assert controller.sock.buffer_put[0] == get_message
@pytest.mark.parametrize(
"axis,is_referenced,get_message,return_msg,exception",
[
(0, True, b":GPPK0\n", b":PPK0,1", None),
(1, True, b":GPPK1\n", b":PPK1,1", None),
(0, False, b":GPPK0\n", b":PPK0,0", None),
(200, False, b":GPPK0\n", b":PPK0,0", ValueError),
],
)
def test_axis_is_referenced(axis, is_referenced, get_message, return_msg, exception):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
if exception is not None:
with pytest.raises(exception):
val = controller.axis_is_referenced(axis)
else:
val = controller.axis_is_referenced(axis)
assert val == is_referenced
assert controller.sock.buffer_put[0] == get_message
@pytest.mark.parametrize(
"return_msg,exception,raised",
[
(b"false", SmaractCommunicationError, False),
(b":E0,1", SmaractErrorCode, True),
(b":E,1", SmaractCommunicationError, True),
(b":E,-1", SmaractCommunicationError, True),
],
)
def test_socket_put_and_receive_raises_exception(return_msg, exception, raised):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
with pytest.raises(exception):
controller.socket_put_and_receive(b"test", raise_if_not_status=True)
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
if raised:
with pytest.raises(exception):
controller.socket_put_and_receive(b"test")
else:
assert controller.socket_put_and_receive(b"test") == return_msg.decode()
@pytest.mark.parametrize(
"mode,get_message,return_msg",
[
(0, b":GCM\n", b":CM0"),
(1, b":GCM\n", b":CM1"),
],
)
def test_communication_mode(mode, get_message, return_msg):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
val = controller.get_communication_mode()
assert controller.sock.buffer_put[0] == get_message
assert val == SmaractCommunicationMode(mode)
@pytest.mark.parametrize(
"is_moving,get_message,return_msg",
[
(0, b":GS0\n", b":S0,0"),
(1, b":GS0\n", b":S0,1"),
(1, b":GS0\n", b":S0,2"),
(0, b":GS0\n", b":S0,3"),
(1, b":GS0\n", b":S0,4"),
(0, b":GS0\n", b":S0,5"),
(0, b":GS0\n", b":S0,6"),
(1, b":GS0\n", b":S0,7"),
(0, b":GS0\n", b":S0,9"),
(0, [b":GS0\n", b":GS0\n"], [b":E0,0", b":S0,9"]),
],
)
def test_axis_is_moving(is_moving, get_message, return_msg):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
val = controller.is_axis_moving(0)
assert val == is_moving
if isinstance(controller.sock.buffer_put, list) and len(controller.sock.buffer_put) == 1:
controller.sock.buffer_put = controller.sock.buffer_put[0]
assert controller.sock.buffer_put == get_message
@pytest.mark.parametrize(
"sensor_id,axis,get_msg,return_msg",
[
(1, 0, b":GST0\n", b":ST0,1"),
(6, 0, b":GST0\n", b":ST0,6"),
(6, 1, b":GST1\n", b":ST1,6"),
],
)
def test_get_sensor_definition(sensor_id, axis, get_msg, return_msg):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
sensor = controller.get_sensor_type(axis)
assert sensor.type_code == sensor_id
@pytest.mark.parametrize(
"move_speed,axis,get_msg,return_msg",
[
(50, 0, b":SCLS0,50000000\n", b":E-1,0"),
(0, 0, b":SCLS0,0\n", b":E-1,0"),
(20.23, 1, b":SCLS1,20230000\n", b":E-1,0"),
],
)
def test_set_move_speed(move_speed, axis, get_msg, return_msg):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
controller.set_closed_loop_move_speed(axis, move_speed)
assert controller.sock.buffer_put[0] == get_msg
@pytest.mark.parametrize(
"pos,axis,hold_time,get_msg,return_msg",
[
(50, 0, None, b":MPA0,50000000,1000\n", b":E0,0"),
(0, 0, 800, b":MPA0,0,800\n", b":E0,0"),
(20.23, 1, None, b":MPA1,20230000,1000\n", b":E0,0"),
],
)
def test_move_axis_to_absolute_position(pos, axis, hold_time, get_msg, return_msg):
controller = SmaractController(socket=SocketMock(host="dummy", port=123))
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
if hold_time is not None:
controller.move_axis_to_absolute_position(axis, pos, hold_time=hold_time)
else:
controller.move_axis_to_absolute_position(axis, pos)
assert controller.sock.buffer_put[0] == get_msg
@pytest.mark.parametrize(
"pos,get_msg,return_msg",
[
(
50,
[b":GPPK0\n", b":MPA0,50000000,1000\n", b":GS0\n", b":GP0\n"],
[b":PPK0,1", b":E0,0", b":S0,0", b":P0,50000000\n"],
),
(
0,
[b":GPPK0\n", b":MPA0,0,1000\n", b":GS0\n", b":GP0\n"],
[b":PPK0,1", b":E0,0", b":S0,0", b":P0,0000000\n"],
),
(
20.23,
[b":GPPK0\n", b":MPA0,20230000,1000\n", b":GS0\n", b":GP0\n"],
[b":PPK0,1", b":E0,0", b":S0,0", b":P0,20230000\n"],
),
(
20.23,
[b":GPPK0\n", b":GPPK0\n", b":MPA0,20230000,1000\n", b":GS0\n", b":GP0\n"],
[b":S0,0", b":PPK0,1", b":E0,0", b":S0,0", b":P0,20230000\n"],
),
],
)
def test_move_axis(pos, get_msg, return_msg):
lsmarA = SmaractMotor(
"A",
name="lsmarA",
host="mpc2680.psi.ch",
port=8085,
sign=1,
socket_cls=SocketMock,
)
lsmarA.stage()
controller = lsmarA.controller
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
lsmarA.move(pos)
assert controller.sock.buffer_put == get_msg
@pytest.mark.parametrize(
"num_axes,get_msg,return_msg",
[
(
1,
[b":S0\n"],
[b":E0,0"],
)
],
)
def test_stop_axis(num_axes, get_msg, return_msg):
lsmarA = SmaractMotor(
"A",
name="lsmarA",
host="mpc2680.psi.ch",
port=8085,
sign=1,
socket_cls=SocketMock,
)
lsmarA.stage()
controller = lsmarA.controller
controller.sock.flush_buffer()
controller.sock.buffer_recv = return_msg
controller.stop_all_axes()
assert controller.sock.buffer_put == get_msg

69
tests/test_socket.py Normal file
View File

@ -0,0 +1,69 @@
import pytest
import socket
from ophyd_devices.utils.socket import SocketIO
class DummySocket:
AF_INET = 2
SOCK_STREAM = 1
def __init__(self) -> None:
self.address_family = None
self.socket_kind = None
self.timeout = None
def socket(self, address_family, socket_kind):
self.address_family = address_family
self.socket_kind = socket_kind
return self
def settimeout(self, timeout):
self.timeout = timeout
def send(self, msg, *args, **kwargs):
self.send_buffer = msg
def connect(self, address):
self.host = address[0]
self.port = address[1]
self.connected = True
def close(self):
self.connected = False
def test_socket_init():
socketio = SocketIO("localhost", 8080)
assert socketio.host == "localhost"
assert socketio.port == 8080
assert socketio.is_open == False
assert socketio.sock.family == socket.AF_INET
assert socketio.sock.type == socket.SOCK_STREAM
def test_socket_put():
dsocket = DummySocket()
socketio = SocketIO("localhost", 8080)
socketio.sock = dsocket
socketio.put(b"message")
assert dsocket.send_buffer == b"message"
def test_open():
dsocket = DummySocket()
socketio = SocketIO("localhost", 8080)
socketio.sock = dsocket
socketio.open()
assert socketio.is_open == True
assert socketio.sock.host == socketio.host
assert socketio.sock.port == socketio.port
def test_close():
socketio = SocketIO("localhost", 8080)
socketio.close()
assert socketio.sock == None
assert socketio.is_open == False

46
tests/utils.py Normal file
View File

@ -0,0 +1,46 @@
class SocketMock:
def __init__(self, host, port):
self.host = host
self.port = port
self.buffer_put = []
self.buffer_recv = [b""]
self.is_open = False
self.open()
def connect(self):
print(f"connecting to {self.host} port {self.port}")
def _put(self, msg_bytes):
self.buffer_put.append(msg_bytes)
print(self.buffer_put)
def _recv(self, buffer_length=1024):
print(self.buffer_recv)
if isinstance(self.buffer_recv, list):
if len(self.buffer_recv) > 0:
ret_val = self.buffer_recv.pop(0)
else:
ret_val = b""
return ret_val
return self.buffer_recv
def _initialize_socket(self):
pass
def put(self, msg):
return self._put(msg)
def receive(self, buffer_length=1024):
return self._recv(buffer_length=buffer_length)
def open(self):
self._initialize_socket()
self.is_open = True
def close(self):
self.sock = None
self.is_open = False
def flush_buffer(self):
self.buffer_put = []
self.buffer_recv = ""