PCO camera integration and stdDAQ cleanup #19

Merged
mohacsi_i merged 14 commits from feature/stddaq-and-pco into main 2025-02-14 13:38:26 +01:00
13 changed files with 1690 additions and 726 deletions

View File

@@ -10,30 +10,20 @@ eyex:
enabled: true
readOnly: false
softwareTrigger: false
# eyey:
# readoutPriority: baseline
# description: X-ray eye axis Y
# deviceClass: tomcat_bec.devices.psimotor.EpicsMotorEC
# deviceConfig:
# prefix: MTEST-X05LA-ES2-XRAYEYE:M2
# deviceTags:
# - xray-eye
# onFailure: buffer
# enabled: true
# readOnly: false
# softwareTrigger: false
# eyez:
# readoutPriority: baseline
# description: X-ray eye axis Z
# deviceClass: tomcat_bec.devices.psimotor.EpicsMotorEC
# deviceConfig:
# prefix: MTEST-X05LA-ES2-XRAYEYE:M3
# deviceTags:
# - xray-eye
# onFailure: buffer
# enabled: true
# readOnly: false
# softwareTrigger: false
eyez:
readoutPriority: baseline
description: X-ray eye axis Z
deviceClass: tomcat_bec.devices.psimotor.EpicsMotorEC
deviceConfig:
prefix: MTEST-X05LA-ES2-XRAYEYE:M3
deviceTags:
- xray-eye
onFailure: buffer
enabled: true
readOnly: false
softwareTrigger: false
femto_mean_curr:
readoutPriority: monitored
description: Femto mean current
@@ -139,6 +129,7 @@ gfcam:
deviceTags:
- camera
- trigger
- gfcam
enabled: true
onFailure: buffer
readOnly: false
@@ -154,6 +145,7 @@ gfdaq:
data_source_name: 'gfcam'
deviceTags:
- std-daq
- gfcam
enabled: true
onFailure: buffer
readOnly: false
@@ -167,6 +159,7 @@ daq_stream0:
url: 'tcp://129.129.95.111:20000'
deviceTags:
- std-daq
- gfcam
enabled: true
onFailure: buffer
readOnly: false
@@ -180,6 +173,52 @@ daq_stream1:
url: 'tcp://129.129.95.111:20001'
deviceTags:
- std-daq
- gfcam
enabled: true
onFailure: buffer
readOnly: false
readoutPriority: monitored
softwareTrigger: false
pcocam:
description: PCO.edge camera client
deviceClass: tomcat_bec.devices.PcoEdge5M
deviceConfig:
prefix: 'X02DA-CCDCAM2:'
deviceTags:
- camera
- trigger
- pcocam
enabled: true
onFailure: buffer
readOnly: false
readoutPriority: monitored
softwareTrigger: true
pcodaq:
description: GigaFrost stdDAQ client
deviceClass: tomcat_bec.devices.StdDaqClient
deviceConfig:
ws_url: 'ws://129.129.95.111:8081'
rest_url: 'http://129.129.95.111:5010'
deviceTags:
- std-daq
- pcocam
enabled: true
onFailure: buffer
readOnly: false
readoutPriority: monitored
softwareTrigger: false
pco_stream0:
description: stdDAQ preview (2 every 555)
deviceClass: tomcat_bec.devices.StdDaqPreviewDetector
deviceConfig:
url: 'tcp://129.129.95.111:20010'
deviceTags:
- std-daq
- pcocam
enabled: true
onFailure: buffer
readOnly: false

View File

@@ -11,5 +11,7 @@ from .grashopper_tomcat import GrashopperTOMCAT
from .psimotor import EpicsMotorMR, EpicsMotorEC
from .gigafrost.gigafrostcamera import GigaFrostCamera
from .gigafrost.pcoedgecamera import PcoEdge5M
from .gigafrost.stddaq_client import StdDaqClient
from .gigafrost.stddaq_preview import StdDaqPreviewDetector

View File

@@ -7,7 +7,8 @@ Created on Thu Jun 27 17:28:43 2024
@author: mohacsi_i
"""
from time import sleep
from ophyd import Signal, Component, EpicsSignal, EpicsSignalRO, Kind, DeviceStatus
from ophyd import Signal, SignalRO, Component, EpicsSignal, EpicsSignalRO, Kind, DeviceStatus
from ophyd.device import DynamicDeviceComponent
from ophyd_devices.interfaces.base_classes.psi_detector_base import (
CustomDetectorMixin,
PSIDetectorBase,
@@ -25,9 +26,11 @@ except ModuleNotFoundError:
try:
from bec_lib import bec_logger
logger = bec_logger.logger
except ModuleNotFoundError:
import logging
logger = logging.getLogger("GfCam")
@@ -37,8 +40,9 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
This class will be called by the custom_prepare_cls attribute of the
detector class.
"""
# pylint: disable=protected-access
def _define_backend_ip(self):
""" Select backend IP address for UDP stream"""
"""Select backend IP address for UDP stream"""
if self.parent.backendUrl.get() == const.BE3_DAFL_CLIENT: # xbl-daq-33
return const.BE3_NORTH_IP, const.BE3_SOUTH_IP
if self.parent.backendUrl.get() == const.BE999_DAFL_CLIENT:
@@ -47,7 +51,7 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
raise RuntimeError(f"Backend {self.parent.backendUrl.get()} not recognized.")
def _define_backend_mac(self):
""" Select backend MAC address for UDP stream"""
"""Select backend MAC address for UDP stream"""
if self.parent.backendUrl.get() == const.BE3_DAFL_CLIENT: # xbl-daq-33
return const.BE3_NORTH_MAC, const.BE3_SOUTH_MAC
if self.parent.backendUrl.get() == const.BE999_DAFL_CLIENT:
@@ -73,7 +77,7 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
self.parent.macSouth.get(),
self.parent.ipSouth.get(),
dest_port,
source_port
source_port,
)
else:
extend_header_table(
@@ -81,20 +85,20 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
self.parent.macNorth.get(),
self.parent.ipNorth.get(),
dest_port,
source_port
source_port,
)
return udp_header_table
def on_init(self) -> None:
""" Initialize the camera, set channel values"""
"""Initialize the camera, set channel values"""
# ToDo: Not sure if it's a good idea to change camera settings upon
# ophyd device startup, i.e. each deviceserver restart.
self._init_gigafrost()
self.parent._initialized = True
def _init_gigafrost(self) -> None:
""" Initialize the camera, set channel values"""
"""Initialize the camera, set channel values"""
# Stop acquisition
self.parent.cmdStartCamera.set(0).wait()
@@ -141,7 +145,7 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
return super().on_init()
def on_stage(self) -> None:
""" Configuration and staging
"""Configuration and staging
In the BEC model ophyd devices must fish out their own configuration from the 'scaninfo'.
I.e. they need to know which parameters are relevant for them at each scan.
@@ -157,25 +161,23 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
logger.warning(
f"[{self.parent.name}] Ophyd device havent ran the initialization sequence,"
"IOC might be in unknown configuration."
)
)
# Fish out our configuration from scaninfo (via explicit or generic addressing)
scanparam = self.parent.scaninfo.scan_msg.info
alias = self.parent.parent.name if self.parent.parent is not None else self.parent.name
# logger.warning(f"[{alias}] Scan parameters:\n{scanparam}")
d = {}
if 'kwargs' in scanparam:
scanargs = scanparam['kwargs']
if 'image_width' in scanargs and scanargs['image_width']!=None:
d['image_width'] = scanargs['image_width']
if 'image_height' in scanargs and scanargs['image_height']!=None:
d['image_height'] = scanargs['image_height']
if 'exp_time' in scanargs and scanargs['exp_time']!=None:
d['exposure_time_ms'] = scanargs['exp_time']
if 'exp_burst' in scanargs and scanargs['exp_burst']!=None:
d['exposure_num_burst'] = scanargs['exp_burst']
if 'acq_mode' in scanargs and scanargs['acq_mode']!=None:
d['acq_mode'] = scanargs['acq_mode']
if "kwargs" in scanparam:
scanargs = scanparam["kwargs"]
if "image_width" in scanargs and scanargs["image_width"] is not None:
d["image_width"] = scanargs["image_width"]
if "image_height" in scanargs and scanargs["image_height"] is not None:
d["image_height"] = scanargs["image_height"]
if "exp_time" in scanargs and scanargs["exp_time"] is not None:
d["exposure_time_ms"] = scanargs["exp_time"]
if "exp_burst" in scanargs and scanargs["exp_burst"] is not None:
d["exposure_num_burst"] = scanargs["exp_burst"]
if "acq_mode" in scanargs and scanargs["acq_mode"] is not None:
d["acq_mode"] = scanargs["acq_mode"]
# elif self.parent.scaninfo.scan_type == "step":
# d['acq_mode'] = "default"
@@ -193,7 +195,7 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
def on_unstage(self) -> None:
"""Specify actions to be executed during unstage.
This step should include checking if the acqusition was successful,
This step should include checking if the acquisition was successful,
and publishing the file location and file event message,
with flagged done to BEC.
"""
@@ -216,13 +218,17 @@ class GigaFrostCameraMixin(CustomDetectorMixin):
Specify actions to be executed upon receiving trigger signal.
Return a DeviceStatus object or None
"""
if self.parent.infoBusyFlag.get() in (0, 'IDLE'):
raise RuntimeError('GigaFrost must be running before triggering')
if self.parent.infoBusyFlag.get() in (0, "IDLE"):
raise RuntimeError("GigaFrost must be running before triggering")
logger.warning(f"[{self.parent.name}] SW triggering gigafrost")
# Soft triggering based on operation mode
if self.parent.autoSoftEnable.get() and self.parent.trigger_mode == 'auto' and self.parent.enable_mode == 'soft':
if (
self.parent.autoSoftEnable.get()
and self.parent.trigger_mode == "auto"
and self.parent.enable_mode == "soft"
):
# BEC teststand operation mode: posedge of SoftEnable if Started
self.parent.cmdSoftEnable.set(0).wait()
self.parent.cmdSoftEnable.set(1).wait()
@@ -253,6 +259,7 @@ class GigaFrostCamera(PSIDetectorBase):
----------
FRAMERATE : Ignored in soft trigger mode, period becomes 2xExposure time
"""
# pylint: disable=too-many-instance-attributes
custom_prepare_cls = GigaFrostCameraMixin
@@ -266,6 +273,14 @@ class GigaFrostCamera(PSIDetectorBase):
cmdSetParam = Component(EpicsSignal, "SET_PARAM.PROC", put_complete=True, kind=Kind.omitted)
cfgAcqMode = Component(EpicsSignal, "ACQMODE", put_complete=True, kind=Kind.config)
array_size = DynamicDeviceComponent(
{
"array_size_x": (EpicsSignalRO, "ROIX", {"auto_monitor": True}),
"array_size_y": (EpicsSignalRO, "ROIY", {"auto_monitor": True}),
},
doc="Size of the array in the XY dimensions",
)
# UDP header
cfgUdpNumPorts = Component(EpicsSignal, "PORTS", put_complete=True, kind=Kind.config)
cfgUdpNumFrames = Component(EpicsSignal, "FRAMENUM", put_complete=True, kind=Kind.config)
@@ -274,24 +289,26 @@ class GigaFrostCamera(PSIDetectorBase):
# Standard camera configs
cfgExposure = Component(
EpicsSignal, "EXPOSURE", put_complete=True, auto_monitor=True, kind=Kind.config)
EpicsSignal, "EXPOSURE", put_complete=True, auto_monitor=True, kind=Kind.config
)
cfgFramerate = Component(
EpicsSignal, "FRAMERATE", put_complete=True, auto_monitor=True, kind=Kind.config)
cfgRoiX = Component(
EpicsSignal, "ROIX", put_complete=True, auto_monitor=True, kind=Kind.config)
cfgRoiY = Component(
EpicsSignal, "ROIY", put_complete=True, auto_monitor=True, kind=Kind.config)
EpicsSignal, "FRAMERATE", put_complete=True, auto_monitor=True, kind=Kind.config
)
cfgRoiX = Component(EpicsSignal, "ROIX", put_complete=True, auto_monitor=True, kind=Kind.config)
cfgRoiY = Component(EpicsSignal, "ROIY", put_complete=True, auto_monitor=True, kind=Kind.config)
cfgScanId = Component(
EpicsSignal, "SCAN_ID", put_complete=True, auto_monitor=True, kind=Kind.config)
EpicsSignal, "SCAN_ID", put_complete=True, auto_monitor=True, kind=Kind.config
)
cfgCntNum = Component(
EpicsSignal, "CNT_NUM", put_complete=True, auto_monitor=True, kind=Kind.config)
EpicsSignal, "CNT_NUM", put_complete=True, auto_monitor=True, kind=Kind.config
)
cfgCorrMode = Component(
EpicsSignal, "CORR_MODE", put_complete=True, auto_monitor=True, kind=Kind.config)
EpicsSignal, "CORR_MODE", put_complete=True, auto_monitor=True, kind=Kind.config
)
# Software signals
cmdSoftEnable = Component(EpicsSignal, "SOFT_ENABLE", put_complete=True)
cmdSoftTrigger = Component(
EpicsSignal, "SOFT_TRIG.PROC", put_complete=True, kind=Kind.omitted)
cmdSoftTrigger = Component(EpicsSignal, "SOFT_TRIG.PROC", put_complete=True, kind=Kind.omitted)
cmdSoftExposure = Component(EpicsSignal, "SOFT_EXP", put_complete=True)
cfgAcqMode = Component(EpicsSignal, "ACQMODE", put_complete=True, kind=Kind.config)
@@ -395,11 +412,7 @@ class GigaFrostCamera(PSIDetectorBase):
kind=Kind.config,
)
cfgCntEndBit = Component(
EpicsSignal,
"CNT_ENDBIT_RBV",
write_pv="CNT_ENDBIT",
put_complete=True,
kind=Kind.config
EpicsSignal, "CNT_ENDBIT_RBV", write_pv="CNT_ENDBIT", put_complete=True, kind=Kind.config
)
# Line swap selection
@@ -449,32 +462,41 @@ class GigaFrostCamera(PSIDetectorBase):
):
# Ugly hack to pass values before on_init()
self._signals_to_be_set = {}
self._signals_to_be_set['auto_soft_enable'] = auto_soft_enable
self._signals_to_be_set['backend_url'] = backend_url
self._signals_to_be_set["auto_soft_enable"] = auto_soft_enable
self._signals_to_be_set["backend_url"] = backend_url
# super() will call the mixin class
super().__init__(prefix=prefix, name=name, kind=kind, read_attrs=read_attrs, configuration_attrs=configuration_attrs, parent=parent, device_manager=device_manager, **kwargs)
super().__init__(
prefix=prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
device_manager=device_manager,
**kwargs,
)
def _init(self):
"""Ugly hack: values must be set before on_init() is called"""
# Additional parameters
self.autoSoftEnable._metadata["write_access"] = False
self.backendUrl._metadata["write_access"] = False
self.autoSoftEnable.put(self._signals_to_be_set['auto_soft_enable'], force=True)
self.backendUrl.put(self._signals_to_be_set['backend_url'], force=True)
self.autoSoftEnable.put(self._signals_to_be_set["auto_soft_enable"], force=True)
self.backendUrl.put(self._signals_to_be_set["backend_url"], force=True)
return super()._init()
def initialize(self):
""" Initialization in separate command"""
"""Initialization in separate command"""
self.custom_prepare._init_gigafrost()
self._initialized = True
def trigger(self) -> DeviceStatus:
""" Sends a software trigger to GigaFrost"""
"""Sends a software trigger to GigaFrost"""
super().trigger()
# There's no status readback from the camera, so we just wait
sleep_time = self.cfgExposure.value*self.cfgCntNum.value*0.001+0.2
sleep_time = self.cfgExposure.value * self.cfgCntNum.value * 0.001 + 0.2
sleep(sleep_time)
return DeviceStatus(self, done=True, success=True, settle_time=sleep_time)
@@ -519,40 +541,40 @@ class GigaFrostCamera(PSIDetectorBase):
# If Bluesky style configure
if d is not None:
# Commonly changed settings
if 'exposure_num_burst' in d:
self.cfgCntNum.set(d['exposure_num_burst']).wait()
if 'exposure_time_ms' in d:
self.cfgExposure.set(d['exposure_time_ms']).wait()
if 'exposure_period_ms' in d:
self.cfgFramerate.set(d['exposure_period_ms']).wait()
if 'image_width' in d:
if d['image_width']%48 !=0:
if "exposure_num_burst" in d:
self.cfgCntNum.set(d["exposure_num_burst"]).wait()
if "exposure_time_ms" in d:
self.cfgExposure.set(d["exposure_time_ms"]).wait()
if "exposure_period_ms" in d:
self.cfgFramerate.set(d["exposure_period_ms"]).wait()
if "image_width" in d:
if d["image_width"] % 48 != 0:
raise RuntimeError(f"[{self.name}] image_width must be divisible by 48")
self.cfgRoiX.set(d['image_width']).wait()
if 'image_height' in d:
if d['image_height']%16 !=0:
self.cfgRoiX.set(d["image_width"]).wait()
if "image_height" in d:
if d["image_height"] % 16 != 0:
raise RuntimeError(f"[{self.name}] image_height must be divisible by 16")
self.cfgRoiY.set(d['image_height']).wait()
self.cfgRoiY.set(d["image_height"]).wait()
# Dont change these
scanid = d.get('scanid', 0)
correction_mode = d.get('correction_mode', 5)
scanid = d.get("scanid", 0)
correction_mode = d.get("correction_mode", 5)
self.cfgScanId.set(scanid).wait()
self.cfgCorrMode.set(correction_mode).wait()
if 'acq_mode' in d:
self.set_acquisition_mode(d['acq_mode'])
if "acq_mode" in d:
self.set_acquisition_mode(d["acq_mode"])
# Commit parameters
self.cmdSetParam.set(1).wait()
def bluestage(self):
""" Bluesky style stage"""
"""Bluesky style stage"""
# Switch to acquiring
self.cmdStartCamera.set(1).wait()
def set_acquisition_mode(self, acq_mode):
""" Set acquisition mode
"""Set acquisition mode
Utility function to quickly select between pre-configured and tested
acquisition modes.
@@ -569,6 +591,7 @@ class GigaFrostCamera(PSIDetectorBase):
self.cfgEnableScheme.set(0).wait()
# Set modes
# self.cmdSoftEnable.set(0).wait()
self.enable_mode = "soft"
self.trigger_mode = "auto"
self.exposure_mode = "timer"
@@ -825,11 +848,11 @@ class GigaFrostCamera(PSIDetectorBase):
The GigaFRoST enable mode. Valid arguments are:
* 'soft':
The GigaFRoST enable signal is supplied through a software
The GigaFRoST enable signal is supplied through a software
signal
* 'external':
The GigaFRoST enable signal is supplied through an external TTL
gating signal from the rotaiton stage or some other control
The GigaFRoST enable signal is supplied through an external TTL
gating signal from the rotaiton stage or some other control
unit
* 'soft+ext':
The GigaFRoST enable signal can be supplied either via the
@@ -842,9 +865,7 @@ class GigaFrostCamera(PSIDetectorBase):
"""
if mode not in const.gf_valid_enable_modes:
raise ValueError(
"Invalid enable mode! Valid modes are:\n{const.gf_valid_enable_modes}"
)
raise ValueError("Invalid enable mode! Valid modes are:\n{const.gf_valid_enable_modes}")
if mode == "soft":
self.cfgEnableExt.set(0).wait()

View File

@@ -1,388 +0,0 @@
# -*- coding: utf-8 -*-
"""
Created on Wed Dec 6 11:33:54 2023
@author: mohacsi_i
"""
from ophyd import Device, Component, EpicsMotor, EpicsSignal, EpicsSignalRO, Kind
from ophyd.status import Status, SubscriptionStatus, StatusBase, DeviceStatus
from time import sleep
import warnings
import numpy as np
import time
from ophyd_devices.epics.devices.psi_detector_base import CustomDetectorMixin, PSIDetectorBase
class HelgeCameraMixin(CustomDetectorMixin):
"""Mixin class to setup the Helge camera bae class.
This class will be called by the custom_prepare_cls attribute of the detector class.
"""
def __init__(self, *_args, parent: Device = None, **_kwargs) -> None:
super().__init__(*_args, parent=parent, **_kwargs)
self.monitor_thread = None
self.stop_monitor = False
self.update_frequency = 1
def set_exposure_time(self, exposure_time: float) -> None:
"""Set the detector framerate.
Args:
exposure_time (float): Desired exposure time in [sec]
"""
if exposure_time is not None:
self.parent.acqExpTime.set(exposure_time).wait()
def prepare_detector_backend(self) -> None:
pass
def prepare_detector(self) -> None:
"""Prepare detector for acquisition.
State machine:
BUSY and SET both low -> BUSY high, SET low -> BUSY low, SET high -> BUSY low, SET low
"""
self.parent.camSetParam.set(1).wait()
def risingEdge(*args, old_value, value, timestamp, **kwargs):
return bool(not old_value and value)
def fallingEdge(*args, old_value, value, timestamp, **kwargs):
return bool(old_value and not value)
# Subscribe and wait for update
status = SubscriptionStatus(self.parent.camSetParam, fallingEdge, settle_time=0.5)
status.wait()
def arm_acquisition(self) -> None:
"""Arm camera for acquisition"""
# Acquisition is only allowed when the IOC is not busy
if self.parent.state in ("OFFLINE", "BUSY", "REMOVED", "RUNNING"):
raise RuntimeError(f"Camera in in state: {self.parent.state}")
# Start the acquisition (this sets parameers and starts acquisition)
self.parent.camStatusCmd.set("Running").wait()
# Subscribe and wait for update
def isRunning(*args, old_value, value, timestamp, **kwargs):
return bool(self.parent.state=="RUNNING")
status = SubscriptionStatus(self.parent.camStatusCode, isRunning, settle_time=0.2)
status.wait()
def stop_detector(self) -> None:
self.camStatusCmd.set("Idle").wait()
# Subscribe and wait for update
def isIdle(*args, old_value, value, timestamp, **kwargs):
return bool(value==2)
status = SubscriptionStatus(self.parent.camStatusCode, isIdle, settle_time=0.5)
status.wait()
def send_data(self) -> None:
"""Send data to monitor endpoint in redis."""
try:
img = self.parent.image.get()
# pylint: disable=protected-access
self.parent._run_subs(sub_type=self.parent.SUB_VALUE, value=img)
except Exception as e:
logger.debug(f"{e} for image with shape {self.parent.image.get().shape}")
def monitor_loop(self) -> None:
"""
Monitor the detector status and send data.
"""
while True:
self.send_data()
time.sleep(1 / self.update_frequency)
if self.parent.state != "RUNNING":
break
if self.stop_monitor:
break
def run_monitor(self) -> None:
"""
Run the monitor loop in a separate thread.
"""
self.monitor_thread = threading.Thread(target=self.monitor_loop, daemon=True)
self.monitor_thread.start()
class HelgeCameraCore(PSIDetectorBase):
"""Ophyd baseclass for Helge camera IOCs
This class provides wrappers for Helge's camera IOCs around SwissFEL and
for high performance SLS 2.0 cameras. The IOC's operation is a bit arcane
and there are different versions and cameras all around. So this device
only covers the absolute basics.
Probably the most important part is the configuration state machine. As
the SET_PARAMS takes care of buffer allocations it might take some time,
as well as afull re-configuration is required every time we change the
binning, roi, etc... This is automatically performed upon starting an
exposure (if it heven't been done before).
The status flag state machine during re-configuration is:
BUSY low, SET low -> BUSY high, SET low -> BUSY low, SET high -> BUSY low, SET low
"""
# Specify Mixin class
custom_prepare_cls = HelgeCameraMixin
USER_ACCESS = ["kickoff"]
# ########################################################################
# General hardware info
camType = Component(EpicsSignalRO, "QUERY", kind=Kind.omitted)
camBoard = Component(EpicsSignalRO, "BOARD", kind=Kind.config)
camError = Component(EpicsSignalRO, "ERRCODE", auto_monitor=True, kind=Kind.config)
camWarning = Component(EpicsSignalRO, "WARNCODE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Acquisition commands
camStatusCmd = Component(EpicsSignal, "CAMERASTATUS", put_complete=True, kind=Kind.config)
# ########################################################################
# Acquisition configuration
acqExpTime = Component(EpicsSignalRO, "EXPOSURE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Configuration state maschine with separate transition states
camStatusCode = Component(EpicsSignalRO, "STATUSCODE", auto_monitor=True, kind=Kind.config)
camSetParam = Component(EpicsSignal, "SET_PARAM", auto_monitor=True, kind=Kind.config)
camSetParamBusy = Component(EpicsSignalRO, "BUSY_SET_PARAM", auto_monitor=True, kind=Kind.config)
camCamera = Component(EpicsSignalRO, "CAMERA", auto_monitor=True, kind=Kind.config)
camCameraBusy = Component(EpicsSignalRO, "BUSY_CAMERA", auto_monitor=True, kind=Kind.config)
camInit= Component(EpicsSignalRO, "INIT", auto_monitor=True, kind=Kind.config)
camInitBusy = Component(EpicsSignalRO, "BUSY_INIT", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Throtled image preview
image = Component(EpicsSignalRO, "FPICTURE", kind=Kind.omitted)
# ########################################################################
# Misc PVs
#camRemoval = Component(EpicsSignalRO, "REMOVAL", auto_monitor=True, kind=Kind.config)
camStateString = Component(EpicsSignalRO, "SS_CAMERA", string=True, auto_monitor=True, kind=Kind.config)
@property
def state(self) -> str:
""" Single word camera state"""
if self.camSetParamBusy.value:
return "BUSY"
if self.camStatusCode.value==2 and self.camInit.value==1:
return "IDLE"
if self.camStatusCode.value==6 and self.camInit.value==1:
return "RUNNING"
#if self.camRemoval.value==0 and self.camInit.value==0:
if self.camInit.value==0:
return "OFFLINE"
#if self.camRemoval.value:
# return "REMOVED"
return "UNKNOWN"
@state.setter
def state(self):
raise ReadOnlyError("State is a ReadOnly property")
def configure(self, d: dict = {}) -> tuple:
if self.state in ["OFFLINE", "REMOVED", "RUNNING"]:
raise RuntimeError(f"Can't change configuration from state {self.state}")
def stage(self) -> list[object]:
""" Start acquisition"""
self.custom_prepare.arm_acquisition()
return super().stage()
def kickoff(self) -> DeviceStatus:
""" Start acquisition"""
return self.stage()
def stop(self):
""" Stop the running acquisition """
self.camStatusCmd.set("Idle").wait()
self.custom_prepare.stop_monitor = True
return super().unstage()
def unstage(self):
""" Stop the running acquisition and unstage the device"""
self.camStatusCmd.set("Idle").wait()
self.custom_prepare.stop_monitor = True
return super().unstage()
class HelgeCameraBase(HelgeCameraCore):
"""Ophyd baseclass for Helge camera IOCs
This class provides wrappers for Helge's camera IOCs around SwissFEL and
for high performance SLS 2.0 cameras. Theese are mostly PCO cameras running
on a special Windows IOC host with lots of RAM and CPU power.
The IOC's operation is a bit arcane, and is documented on the "read the code"
level. However the most important part is the state machine of 7+1 PV signals:
INIT
BUSY_INIT
SET_PARAM
BUSY_SET_PARAM
CAMERA
BUSY_CAMERA
CAMERASTATUSCODE
CAMERASTATUS
"""
USER_ACCESS = ["describe", "shape", "bin", "roi"]
# ########################################################################
# Additional status info
busy = Component(EpicsSignalRO, "BUSY", auto_monitor=True, kind=Kind.config)
camState = Component(EpicsSignalRO, "SS_CAMERA", auto_monitor=True, kind=Kind.config)
camProgress = Component(EpicsSignalRO, "CAMPROGRESS", auto_monitor=True, kind=Kind.config)
camRate = Component(EpicsSignalRO, "CAMRATE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Acquisition configuration
acqMode = Component(EpicsSignalRO, "ACQMODE", auto_monitor=True, kind=Kind.config)
acqDelay = Component(EpicsSignalRO, "DELAY", auto_monitor=True, kind=Kind.config)
acqTriggerEna = Component(EpicsSignalRO, "TRIGGER", auto_monitor=True, kind=Kind.config)
#acqTriggerSource = Component(EpicsSignalRO, "TRIGGERSOURCE", auto_monitor=True, kind=Kind.config)
#acqTriggerEdge = Component(EpicsSignalRO, "TRIGGEREDGE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Image size settings
# Priority is: binning -> roi -> final size
pxBinX = Component(EpicsSignal, "BINX", put_complete=True, auto_monitor=True, kind=Kind.config)
pxBinY = Component(EpicsSignal, "BINY", put_complete=True, auto_monitor=True, kind=Kind.config)
pxRoiX_lo = Component(EpicsSignal, "REGIONX_START", put_complete=True, auto_monitor=True, kind=Kind.config)
pxRoiX_hi = Component(EpicsSignal, "REGIONX_END", put_complete=True, auto_monitor=True, kind=Kind.config)
pxRoiY_lo = Component(EpicsSignal, "REGIONY_START", put_complete=True, auto_monitor=True, kind=Kind.config)
pxRoiY_hi = Component(EpicsSignal, "REGIONY_END", put_complete=True, auto_monitor=True, kind=Kind.config)
pxNumX = Component(EpicsSignalRO, "WIDTH", auto_monitor=True, kind=Kind.config)
pxNumY = Component(EpicsSignalRO, "HEIGHT", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Buffer configuration
bufferRecMode = Component(EpicsSignalRO, "RECMODE", auto_monitor=True, kind=Kind.config)
bufferStoreMode = Component(EpicsSignalRO, "STOREMODE", auto_monitor=True, kind=Kind.config)
fileRecMode = Component(EpicsSignalRO, "RECMODE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# File interface
camFileFormat = Component(EpicsSignal, "FILEFORMAT", put_complete=True, kind=Kind.config)
camFilePath = Component(EpicsSignal, "FILEPATH", put_complete=True, kind=Kind.config)
camFileName = Component(EpicsSignal, "FILENAME", put_complete=True, kind=Kind.config)
camFileNr = Component(EpicsSignal, "FILENR", put_complete=True, kind=Kind.config)
camFilePath = Component(EpicsSignal, "FILEPATH", put_complete=True, kind=Kind.config)
camFileTransferStart = Component(EpicsSignal, "FTRANSFER", put_complete=True, kind=Kind.config)
camFileTransferStop = Component(EpicsSignal, "SAVESTOP", put_complete=True, kind=Kind.config)
def configure(self, d: dict = {}) -> tuple:
"""
Camera configuration instructions:
After setting the corresponding PVs, one needs to process SET_PARAM and wait until
BUSY_SET_PARAM goes high and low, followed by SET_PARAM goes high and low. This will
both send the settings to the camera and allocate the necessary buffers in the correct
size and shape (that takes time). Starting the exposure with CAMERASTATUS will also
call SET_PARAM, but it might take long.
"""
old = self.read_configuration()
super().configure(d)
if "exptime" in d:
exposure_time = d['exptime']
if exposure_time is not None:
self.acqExpTime.set(exposure_time).wait()
if "roi" in d:
roi = d["roi"]
if not isinstance(roi, (list, tuple)):
raise ValueError(f"Unknown ROI data type {type(roi)}")
if not len(roi[0])==2 and len(roi[1])==2:
raise ValueError(f"Unknown ROI shape: {roi}")
# Values are rounded to multiples of 16
self.pxRoiX_lo.set(roi[0][0]).wait()
self.pxRoiX_hi.set(roi[0][1]).wait()
self.pxRoiY_lo.set(roi[1][0]).wait()
self.pxRoiY_hi.set(roi[1][1]).wait()
if "bin" in d:
binning = d["bin"]
if not isinstance(binning, (list, tuple)):
raise ValueError(f"Unknown BINNING data type {type(binning)}")
if not len(binning)==2:
raise ValueError(f"Unknown ROI shape: {binning}")
self.pxBinX.set(binning[0]).wait()
self.pxBinY.set(binning[1]).wait()
# State machine
# Initial: BUSY and SET both low
# 1. BUSY set to high
# 2. BUSY goes low, SET goes high
# 3. SET goes low
self.camSetParam.set(1).wait()
def risingEdge(*args, old_value, value, timestamp, **kwargs):
return bool(not old_value and value)
def fallingEdge(*args, old_value, value, timestamp, **kwargs):
return bool(old_value and not value)
# Subscribe and wait for update
status = SubscriptionStatus(self.camSetParam, fallingEdge, settle_time=0.5)
status.wait()
new = self.read_configuration()
return (old, new)
@property
def shape(self):
return (int(self.pxNumX.value), int(self.pxNumY.value))
@shape.setter
def shape(self):
raise ReadOnlyError("Shape is a ReadOnly property")
@property
def bin(self):
return (int(self.pxBinX.value), int(self.pxBinY.value))
@bin.setter
def bin(self):
raise ReadOnlyError("Bin is a ReadOnly property")
@property
def roi(self):
return ((int(self.pxRoiX_lo.value), int(self.pxRoiX_hi.value)), (int(self.pxRoiY_lo.value), int(self.pxRoiY_hi.value)))
@roi.setter
def roi(self):
raise ReadOnlyError("Roi is a ReadOnly property")
# Automatically connect to test camera if directly invoked
if __name__ == "__main__":
# Drive data collection
cam = HelgeCameraBase("SINBC02-DSRM310:", name="mcpcam")
cam.wait_for_connection()

View File

@@ -0,0 +1,187 @@
# -*- coding: utf-8 -*-
"""
Standard DAQ preview image stream module
Created on Thu Jun 27 17:28:43 2024
@author: mohacsi_i
"""
from time import sleep, time
from threading import Thread
import zmq
from ophyd import Device, Signal, Component, Kind
from ophyd_devices.interfaces.base_classes.psi_detector_base import (
CustomDetectorMixin,
PSIDetectorBase,
)
from bec_lib import bec_logger
logger = bec_logger.logger
ZMQ_TOPIC_FILTER = b""
class PcoTestConsumerMixin(CustomDetectorMixin):
"""Setup class for the standard DAQ preview stream
Parent class: CustomDetectorMixin
"""
# pylint: disable=protected-access
def on_stage(self):
"""Start listening for preview data stream"""
if self.parent._mon is not None:
self.parent.unstage()
sleep(0.5)
self.parent.connect()
self._stop_polling = False
self.parent._mon = Thread(target=self.poll, daemon=True)
self.parent._mon.start()
def on_unstage(self):
"""Stop a running preview"""
if self.parent._mon is not None:
self._stop_polling = True
# Might hang on recv_multipart
self.parent._mon.join(timeout=1)
# So also disconnect the socket
self.parent.disconnect()
def on_stop(self):
"""Stop a running preview"""
self.parent.disconnect()
def poll(self):
"""Collect streamed updates"""
try:
t_last = time()
while True:
try:
# Exit loop and finish monitoring
if self._stop_polling:
logger.info(f"[{self.parent.name}]\tDetaching monitor")
break
# pylint: disable=no-member
r = self.parent._socket.recv()
# Length and throtling checks
t_curr = time()
t_elapsed = t_curr - t_last
if t_elapsed < self.parent.throttle.get():
continue
# # Unpack the Array V1 reply to metadata and array data
# meta, data = r
# print(meta)
# # Update image and update subscribers
# header = json.loads(meta)
# if header["type"] == "uint16":
# image = np.frombuffer(data, dtype=np.uint16)
# if image.size != np.prod(header['shape']):
# err = f"Unexpected array size of {image.size} for header: {header}"
# raise ValueError(err)
# image = image.reshape(header['shape'])
# # Update image and update subscribers
# self.parent.frame.put(header['frame'], force=True)
# self.parent.image_shape.put(header['shape'], force=True)
# self.parent.image.put(image, force=True)
# self.parent._last_image = image
# self.parent._run_subs(sub_type=self.parent.SUB_MONITOR, value=image)
t_last = t_curr
# logger.info(
# f"[{self.parent.name}] Updated frame {header['frame']}\t"
# f"Shape: {header['shape']}\tMean: {np.mean(image):.3f}"
# )
except ValueError:
# Happens when ZMQ partially delivers the multipart message
pass
except zmq.error.Again:
# Happens when receive queue is empty
sleep(0.1)
except Exception as ex:
logger.info(f"[{self.parent.name}]\t{str(ex)}")
raise
finally:
try:
self.parent._socket.disconnect()
except RuntimeError:
pass
self.parent._mon = None
logger.info(f"[{self.parent.name}]\tDetaching monitor")
class PcoTestConsumer(PSIDetectorBase):
"""Detector wrapper class around the StdDaq preview image stream.
This was meant to provide live image stream directly from the StdDAQ.
Note that the preview stream must be already throtled in order to cope
with the incoming data and the python class might throttle it further.
You can add a preview widget to the dock by:
cam_widget = gui.add_dock('cam_dock1').add_widget('BECFigure').image('daq_stream1')
"""
# Subscriptions for plotting image
USER_ACCESS = ["get_last_image"]
SUB_MONITOR = "device_monitor_2d"
_default_sub = SUB_MONITOR
custom_prepare_cls = PcoTestConsumerMixin
# Status attributes
url = Component(Signal, kind=Kind.config)
throttle = Component(Signal, value=0.25, kind=Kind.config)
frame = Component(Signal, kind=Kind.hinted)
image_shape = Component(Signal, kind=Kind.normal)
# FIXME: The BEC client caches the read()s from the last 50 scans
image = Component(Signal, kind=Kind.omitted)
_last_image = None
_mon = None
_socket = None
def __init__(
self, *args, url: str = "tcp://129.129.95.38:20000", parent: Device = None, **kwargs
) -> None:
super().__init__(*args, parent=parent, **kwargs)
self.url._metadata["write_access"] = False
self.image._metadata["write_access"] = False
self.frame._metadata["write_access"] = False
self.image_shape._metadata["write_access"] = False
self.url.set(url, force=True).wait()
def connect(self):
"""Connect to te StDAQs PUB-SUB streaming interface
StdDAQ may reject connection for a few seconds when it restarts,
so if it fails, wait a bit and try to connect again.
"""
# pylint: disable=no-member
# Socket to talk to server
context = zmq.Context()
self._socket = context.socket(zmq.PULL)
try:
self._socket.connect(self.url.get())
except ConnectionRefusedError:
sleep(1)
self._socket.connect(self.url.get())
def disconnect(self):
"""Disconnect"""
try:
if self._socket is not None:
self._socket.disconnect(self.url.get())
except zmq.ZMQError:
pass
finally:
self._socket = None
def get_image(self):
return self._last_image
# Automatically connect to MicroSAXS testbench if directly invoked
if __name__ == "__main__":
daq = PcoTestConsumerMixin(url="tcp://129.129.106.124:8080", name="preview")
daq.wait_for_connection()

View File

@@ -0,0 +1,473 @@
# -*- coding: utf-8 -*-
"""
Created on Wed Dec 6 11:33:54 2023
@author: mohacsi_i
"""
import time
from ophyd import Component, EpicsSignal, EpicsSignalRO, Kind
from ophyd.status import SubscriptionStatus, DeviceStatus
from ophyd_devices import BECDeviceBase
from ophyd_devices.interfaces.base_classes.psi_detector_base import (
CustomDetectorMixin as CustomPrepare,
)
try:
from bec_lib import bec_logger
logger = bec_logger.logger
except ModuleNotFoundError:
import logging
logger = logging.getLogger("PcoEdgeCam")
class PcoEdgeCameraMixin(CustomPrepare):
"""Mixin class to setup the Helge camera bae class.
This class will be called by the custom_prepare_cls attribute of the detector class.
"""
# pylint: disable=protected-access
def on_stage(self) -> None:
"""Configure and arm PCO.Edge camera for acquisition"""
# PCO can finish a run without explicit unstaging
if self.parent.state not in ("IDLE"):
logger.warning(
f"Trying to stage the camera from state {self.parent.state}, unstaging it first!"
)
self.parent.unstage()
time.sleep(0.5)
# Fish out our configuration from scaninfo (via explicit or generic addressing)
scanparam = self.parent.scaninfo.scan_msg.info
d = {}
if "kwargs" in scanparam:
scanargs = scanparam["kwargs"]
if "exp_burst" in scanargs and scanargs["exp_burst"] is not None:
d["exposure_num_burst"] = scanargs["exp_burst"]
if "image_width" in scanargs and scanargs["image_width"] is not None:
d["image_width"] = scanargs["image_width"]
if "image_height" in scanargs and scanargs["image_height"] is not None:
d["image_height"] = scanargs["image_height"]
if "exp_time" in scanargs and scanargs["exp_time"] is not None:
d["exposure_time_ms"] = scanargs["exp_time"]
if "exp_period" in scanargs and scanargs["exp_period"] is not None:
d["exposure_period_ms"] = scanargs["exp_period"]
# if 'exp_burst' in scanargs and scanargs['exp_burst'] is not None:
# d['exposure_num_burst'] = scanargs['exp_burst']
# if 'acq_mode' in scanargs and scanargs['acq_mode'] is not None:
# d['acq_mode'] = scanargs['acq_mode']
# elif self.parent.scaninfo.scan_type == "step":
# d['acq_mode'] = "default"
if "pco_store_mode" in scanargs and scanargs["pco_store_mode"] is not None:
d["store_mode"] = scanargs["pco_store_mode"]
if "pco_data_format" in scanargs and scanargs["pco_data_format"] is not None:
d["data_format"] = scanargs["pco_data_format"]
# Perform bluesky-style configuration
if len(d) > 0:
logger.warning(f"[{self.parent.name}] Configuring with:\n{d}")
self.parent.configure(d=d)
# ARM the camera
self.parent.bluestage()
def on_unstage(self) -> None:
"""Disarm the PCO.Edge camera"""
self.parent.blueunstage()
def on_stop(self) -> None:
"""Stop the PCO.Edge camera"""
self.parent.blueunstage()
def on_trigger(self) -> None | DeviceStatus:
"""Trigger mode operation
Use it to repeatedly record a fixed number of frames and send it to stdDAQ. The method waits
for the acquisition and data transfer to complete.
NOTE: Maciej confirmed that sparse data is no problem to the stdDAQ.
TODO: Optimize data transfer to launch at end and check completion at the beginning.
"""
# Ensure that previous data transfer finished
# def sentIt(*args, value, timestamp, **kwargs):
# return value==0
# status = SubscriptionStatus(self.parent.file_savebusy, sentIt, timeout=120)
# status.wait()
# Not sure if it always sends the first batch of images or the newest
def wait_bufferreset(*, old_value, value, timestamp, **_):
return (value < old_value) or (value == 0)
self.parent.buffer_clear.set(1).wait()
status = SubscriptionStatus(self.parent.buffer_used, wait_bufferreset, timeout=5)
status.wait()
t_expected = (
self.parent.acquire_time.get() + self.parent.acquire_delay.get()
) * self.parent.file_savestop.get()
# Wait until the buffer fills up with enough images
def wait_acquisition(*, value, timestamp, **_):
num_target = self.parent.file_savestop.get()
# logger.warning(f"{value} of {num_target}")
return bool(value >= num_target)
max_wait = max(5, 5 * t_expected)
status = SubscriptionStatus(
self.parent.buffer_used, wait_acquisition, timeout=max_wait, settle_time=0.2
)
status.wait()
# Then start file transfer (need to get the save busy flag update)
# self.parent.file_transfer.set(1, settle_time=0.2).wait()
self.parent.file_transfer.set(1).wait()
# And wait until the images have been sent
# NOTE: this does not wait for new value, the first check will be
# against values from the previous cycle, i.e. pass automatically.
t_start = time.time()
def wait_sending(*args, old_value, value, timestamp, **kwargs):
t_elapsed = timestamp - t_start
# logger.warning(f"{old_value}\t{value}\t{t_elapsed}")
return old_value == 1 and value == 0 and t_elapsed > 0
status = SubscriptionStatus(
self.parent.file_savebusy, wait_sending, timeout=120, settle_time=0.2
)
status.wait()
class HelgeCameraBase(BECDeviceBase):
"""Ophyd baseclass for Helge camera IOCs
This class provides wrappers for Helge's camera IOCs around SwissFEL and
for high performance SLS 2.0 cameras. The IOC's operation is a bit arcane
and there are different versions and cameras all around. So this device
only covers the absolute basics.
Probably the most important part is the configuration state machine. As
the SET_PARAMS takes care of buffer allocations it might take some time,
as well as a full re-configuration is required every time we change the
binning, roi, etc... This is automatically performed upon starting an
exposure (if it heven't been done before).
The status flag state machine during re-configuration is:
BUSY low, SET low -> BUSY high, SET low -> BUSY low, SET high -> BUSY low, SET low
UPDATE: Data sending operation modes
- Switch to ZMQ streaming by setting FILEFORMAT to ZEROMQ
- Set SAVESTART and SAVESTOP to select a ROI of image indices
- Start file transfer with FTRANSFER.
The ZMQ connection operates in PUSH-PULL mode, i.e. it needs incoming connection.
STOREMODE sets the acquisition mode:
if STOREMODE == Recorder
Fills up the buffer with images. Here SAVESTART and SAVESTOP selects a ROI
of image indices to be streamed out (i.e. maximum buffer_size number of images)
if STOREMODE == FIFO buffer
Continously streams out data using the buffer as a FIFO queue.
Here SAVESTART and SAVESTOP selects a ROI of image indices to be streamed continously
(i.e. a large SAVESTOP streams indefinitely). Note that in FIFO mode buffer reads are
destructive. to prevent this, we don't have EPICS preview
"""
# ########################################################################
# General hardware info (in AD nomenclature)
manufacturer = Component(EpicsSignalRO, "QUERY", kind=Kind.config, doc="Camera model info")
model = Component(EpicsSignalRO, "BOARD", kind=Kind.omitted, doc="Camera board info")
# ########################################################################
# Acquisition commands
camStatusCmd = Component(EpicsSignal, "CAMERASTATUS", put_complete=True, kind=Kind.config)
# ########################################################################
# Acquisition configuration (in AD nomenclature)
acquire_time = Component(
EpicsSignal, "EXPOSURE", put_complete=True, auto_monitor=True, kind=Kind.config
)
acquire_delay = Component(
EpicsSignal, "DELAY", put_complete=True, auto_monitor=True, kind=Kind.config
)
trigger_mode = Component(
EpicsSignal, "TRIGGER", put_complete=True, auto_monitor=True, kind=Kind.config
)
# ########################################################################
# Image size configuration (in AD nomenclature)
bin_x = Component(EpicsSignal, "BINX", put_complete=True, auto_monitor=True, kind=Kind.config)
bin_y = Component(EpicsSignal, "BINY", put_complete=True, auto_monitor=True, kind=Kind.config)
array_size_x = Component(
EpicsSignalRO, "WIDTH", auto_monitor=True, kind=Kind.config, doc="Final image width"
)
array_size_y = Component(
EpicsSignalRO, "HEIGHT", auto_monitor=True, kind=Kind.config, doc="Final image height"
)
# ########################################################################
# General hardware info
camError = Component(EpicsSignalRO, "ERRCODE", auto_monitor=True, kind=Kind.config)
camWarning = Component(EpicsSignalRO, "WARNCODE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Buffer configuration
bufferRecMode = Component(EpicsSignalRO, "RECMODE", auto_monitor=True, kind=Kind.config)
bufferStoreMode = Component(EpicsSignal, "STOREMODE", auto_monitor=True, kind=Kind.config)
fileRecMode = Component(EpicsSignalRO, "RECMODE", auto_monitor=True, kind=Kind.config)
buffer_used = Component(EpicsSignalRO, "PIC_BUFFER", auto_monitor=True, kind=Kind.normal)
buffer_size = Component(EpicsSignalRO, "PIC_MAX", auto_monitor=True, kind=Kind.normal)
buffer_clear = Component(EpicsSignal, "CLEARMEM", put_complete=True, kind=Kind.omitted)
# ########################################################################
# File saving interface
cam_data_rate = Component(EpicsSignalRO, "CAMRATE", auto_monitor=True, kind=Kind.normal)
file_data_rate = Component(EpicsSignalRO, "FILERATE", auto_monitor=True, kind=Kind.normal)
file_savestart = Component(EpicsSignal, "SAVESTART", put_complete=True, kind=Kind.config)
file_savestop = Component(EpicsSignal, "SAVESTOP", put_complete=True, kind=Kind.config)
file_format = Component(EpicsSignal, "FILEFORMAT", put_complete=True, kind=Kind.config)
file_transfer = Component(EpicsSignal, "FTRANSFER", put_complete=True, kind=Kind.config)
file_savebusy = Component(EpicsSignalRO, "FILESAVEBUSY", auto_monitor=True, kind=Kind.normal)
# ########################################################################
# Configuration state maschine with separate transition states
camStatusCode = Component(EpicsSignalRO, "STATUSCODE", auto_monitor=True, kind=Kind.config)
camSetParam = Component(EpicsSignal, "SET_PARAM", auto_monitor=True, kind=Kind.config)
camSetParamBusy = Component(
EpicsSignalRO, "BUSY_SET_PARAM", auto_monitor=True, kind=Kind.config
)
camCamera = Component(EpicsSignalRO, "CAMERA", auto_monitor=True, kind=Kind.config)
camCameraBusy = Component(EpicsSignalRO, "BUSY_CAMERA", auto_monitor=True, kind=Kind.config)
camInit = Component(EpicsSignalRO, "INIT", auto_monitor=True, kind=Kind.config)
camInitBusy = Component(EpicsSignalRO, "BUSY_INIT", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Throtled image preview
image = Component(EpicsSignalRO, "FPICTURE", kind=Kind.omitted, doc="Throttled image preview")
# ########################################################################
# Misc PVs
# camRemoval = Component(EpicsSignalRO, "REMOVAL", auto_monitor=True, kind=Kind.config)
camStateString = Component(
EpicsSignalRO, "SS_CAMERA", string=True, auto_monitor=True, kind=Kind.config
)
@property
def state(self) -> str:
"""Single word camera state"""
if self.camSetParamBusy.value:
return "BUSY"
if self.camStatusCode.value == 2 and self.camInit.value == 1:
return "IDLE"
if self.camStatusCode.value == 6 and self.camInit.value == 1:
return "RUNNING"
# if self.camRemoval.value==0 and self.camInit.value==0:
if self.camInit.value == 0:
return "OFFLINE"
# if self.camRemoval.value:
# return "REMOVED"
return "UNKNOWN"
@state.setter
def state(self):
raise RuntimeError("State is a ReadOnly property")
def configure(self, d: dict = {}) -> tuple:
"""Configure the base Helge camera device
Parameters as 'd' dictionary
----------------------------
num_images : int
Number of images to be taken during each scan. Meaning depends on
store mode.
exposure_time_ms : float
Exposure time [ms], usually gets set back to 20 ms
exposure_period_ms : float
Exposure period [ms], up to 200 ms.
store_mode : str
Buffer operation mode
*'Recorder' to record in buffer
*'FIFO buffer' for continous streaming
data_format : str
Usually set to 'ZEROMQ'
"""
if self.state not in ("IDLE"):
raise RuntimeError(f"Can't change configuration from state {self.state}")
# If Bluesky style configure
if d is not None:
# Commonly changed settings
if "exposure_num_burst" in d:
self.file_savestop.set(d["exposure_num_burst"]).wait()
if "exposure_time_ms" in d:
self.acquire_time.set(d["exposure_time_ms"]).wait()
if "exposure_period_ms" in d:
self.acquire_delay.set(d["exposure_period_ms"]).wait()
if "exposure_period_ms" in d:
self.acquire_delay.set(d["exposure_period_ms"]).wait()
if "store_mode" in d:
self.bufferStoreMode.set(d["store_mode"]).wait()
if "data_format" in d:
self.file_format.set(d["data_format"]).wait()
# State machine
# Initial: BUSY and SET both low
# 0. Write 1 to SET_PARAM
# 1. BUSY goes high, SET stays low
# 2. BUSY goes low, SET goes high
# 3. BUSY stays low, SET goes low
# So we need a 'negedge' on SET_PARAM
self.camSetParam.set(1).wait()
def negedge(*, old_value, value, timestamp, **_):
return bool(old_value and not value)
# Subscribe and wait for update
status = SubscriptionStatus(self.camSetParam, negedge, timeout=5, settle_time=0.5)
status.wait()
def bluestage(self):
"""Bluesky style stage: arm the detector"""
logger.warning("Staging PCO")
# Acquisition is only allowed when the IOC is not busy
if self.state in ("OFFLINE", "BUSY", "REMOVED", "RUNNING"):
raise RuntimeError(f"Camera in in state: {self.state}")
if (
self.bufferStoreMode.get() in ("Recorder", 0)
and self.file_savestop.get() > self.buffer_size.get()
):
logger.warning(
f"You'll send empty images, {self.file_savestop.get()} is above buffer size"
)
# Start the acquisition (this sets parameers and starts acquisition)
self.camStatusCmd.set("Running").wait()
# Subscribe and wait for update
def is_running(*, value, timestamp, **_):
return bool(value == 6)
status = SubscriptionStatus(self.camStatusCode, is_running, timeout=5, settle_time=0.2)
status.wait()
def blueunstage(self):
"""Bluesky style unstage: stop the detector"""
self.camStatusCmd.set("Idle").wait()
# Data streaming is stopped by setting the max index to 0
# FIXME: This might interrupt data transfer
self.file_savestop.set(0).wait()
def bluekickoff(self):
"""Start data transfer
TODO: Need to revisit this once triggering is complete
"""
self.file_transfer.set(1).wait()
class PcoEdge5M(HelgeCameraBase):
"""Ophyd baseclass for PCO.Edge cameras
This class provides wrappers for Helge's camera IOCs around SwissFEL and
for high performance SLS 2.0 cameras. Theese are mostly PCO cameras running
on a special Windows IOC host with lots of RAM and CPU power.
"""
custom_prepare_cls = PcoEdgeCameraMixin
USER_ACCESS = ["bluestage", "blueunstage", "bluekickoff"]
# ########################################################################
# Additional status info
busy = Component(EpicsSignalRO, "BUSY", auto_monitor=True, kind=Kind.config)
camState = Component(EpicsSignalRO, "SS_CAMERA", auto_monitor=True, kind=Kind.config)
camProgress = Component(EpicsSignalRO, "CAMPROGRESS", auto_monitor=True, kind=Kind.config)
camRate = Component(EpicsSignalRO, "CAMRATE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Acquisition configuration
acqMode = Component(EpicsSignalRO, "ACQMODE", auto_monitor=True, kind=Kind.config)
acqDelay = Component(EpicsSignalRO, "DELAY", auto_monitor=True, kind=Kind.config)
acqTriggerEna = Component(EpicsSignalRO, "TRIGGER", auto_monitor=True, kind=Kind.config)
# acqTriggerSource = Component(
# EpicsSignalRO, "TRIGGERSOURCE", auto_monitor=True, kind=Kind.config)
# acqTriggerEdge = Component(EpicsSignalRO, "TRIGGEREDGE", auto_monitor=True, kind=Kind.config)
# ########################################################################
# Image size settings
# Priority is: binning -> roi -> final size
pxRoiX_lo = Component(
EpicsSignal, "REGIONX_START", put_complete=True, auto_monitor=True, kind=Kind.config
)
pxRoiX_hi = Component(
EpicsSignal, "REGIONX_END", put_complete=True, auto_monitor=True, kind=Kind.config
)
pxRoiY_lo = Component(
EpicsSignal, "REGIONY_START", put_complete=True, auto_monitor=True, kind=Kind.config
)
pxRoiY_hi = Component(
EpicsSignal, "REGIONY_END", put_complete=True, auto_monitor=True, kind=Kind.config
)
def configure(self, d: dict = {}) -> tuple:
"""
Camera configuration instructions:
After setting the corresponding PVs, one needs to process SET_PARAM and wait until
BUSY_SET_PARAM goes high and low, followed by SET_PARAM goes high and low. This will
both send the settings to the camera and allocate the necessary buffers in the correct
size and shape (that takes time). Starting the exposure with CAMERASTATUS will also
call SET_PARAM, but it might take long.
NOTE:
The camera IOC will automatically round up RoiX coordinates to the
next multiple of 160. This means that configure can only change image
width in steps of 320 pixels (or manually of 160). Roi
Parameters as 'd' dictionary
----------------------------
exposure_time_ms : float, optional
Exposure time [ms].
exposure_period_ms : float, optional
Exposure period [ms], ignored in soft trigger mode.
image_width : int, optional
ROI size in the x-direction, multiple of 320 [pixels]
image_height : int, optional
ROI size in the y-direction, multiple of 2 [pixels]
image_binx : int optional
Binning along image width [pixels]
image_biny: int, optional
Binning along image height [pixels]
acq_mode : str, not yet implemented
Select one of the pre-configured trigger behavior
"""
if d is not None:
# Need to be smart how we set the ROI....
# Image sensor is 2560x2160 (X and Y)
# Values are rounded to multiples of 16
if "image_width" in d and d["image_width"] is not None:
width = d["image_width"]
self.pxRoiX_lo.set(2560 / 2 - width / 2).wait()
self.pxRoiX_hi.set(2560 / 2 + width / 2).wait()
if "image_height" in d and d["image_height"] is not None:
height = d["image_height"]
self.pxRoiY_lo.set(2160 / 2 - height / 2).wait()
self.pxRoiY_hi.set(2160 / 2 + height / 2).wait()
if "image_binx" in d and d["image_binx"] is not None:
self.bin_x.set(d["image_binx"]).wait()
if "image_biny" in d and d["image_biny"] is not None:
self.bin_y.set(d["image_biny"]).wait()
# Call super() to commit the changes
super().configure(d)
# Automatically connect to test camera if directly invoked
if __name__ == "__main__":
# Drive data collection
cam = PcoEdge5M("X02DA-CCDCAM2:", name="mcpcam")
cam.wait_for_connection()

View File

@@ -10,25 +10,28 @@ import json
from time import sleep
from threading import Thread
import requests
import os
from ophyd import Device, Signal, Component, Kind, Staged
from ophyd import Signal, Component, Kind
from ophyd.status import SubscriptionStatus
from ophyd.flyers import FlyerInterface
from websockets.sync.client import connect, ClientConnection
from websockets.exceptions import ConnectionClosedOK, ConnectionClosedError
from ophyd_devices.interfaces.base_classes.psi_detector_base import PSIDetectorBase as PSIDeviceBase
from ophyd_devices.interfaces.base_classes.psi_detector_base import CustomDetectorMixin as CustomDeviceMixin
from ophyd_devices.interfaces.base_classes.psi_detector_base import (
CustomDetectorMixin as CustomDeviceMixin,
)
from bec_lib import bec_logger
logger = bec_logger.logger
class StdDaqMixin(CustomDeviceMixin):
# parent : StdDaqClient
# pylint: disable=protected-access
_mon = None
def on_stage(self) -> None:
""" Configuration and staging
"""Configuration and staging
In the BEC model ophyd devices must fish out their own configuration from the 'scaninfo'.
I.e. they need to know which parameters are relevant for them at each scan.
@@ -38,16 +41,30 @@ class StdDaqMixin(CustomDeviceMixin):
# Fish out our configuration from scaninfo (via explicit or generic addressing)
# NOTE: Scans don't have to fully configure the device
d = {}
if 'kwargs' in self.parent.scaninfo.scan_msg.info:
scanargs = self.parent.scaninfo.scan_msg.info['kwargs']
if 'image_width' in scanargs and scanargs['image_width'] != None:
d['image_width'] = scanargs['image_width']
if 'image_height' in scanargs and scanargs['image_height'] != None:
d['image_height'] = scanargs['image_height']
if 'nr_writers' in scanargs and scanargs['nr_writers'] != None:
d['nr_writers'] = scanargs['nr_writers']
if 'file_path' in scanargs and scanargs['file_path']!=None:
self.parent.file_path.set(scanargs['file_path']).wait()
if "kwargs" in self.parent.scaninfo.scan_msg.info:
scanargs = self.parent.scaninfo.scan_msg.info["kwargs"]
if "image_width" in scanargs and scanargs["image_width"] is not None:
d["image_width"] = scanargs["image_width"]
if "image_height" in scanargs and scanargs["image_height"] is not None:
d["image_height"] = scanargs["image_height"]
if "nr_writers" in scanargs and scanargs["nr_writers"] is not None:
d["nr_writers"] = scanargs["nr_writers"]
if "file_path" in scanargs and scanargs["file_path"] is not None:
self.parent.file_path.set(scanargs["file_path"].replace("data", "gpfs")).wait()
print(scanargs["file_path"])
if os.path.isdir(scanargs["file_path"]):
print("isdir")
pass
else:
print("creating")
try:
os.makedirs(scanargs["file_path"], 0o777)
os.system("chmod -R 777 " + scanargs["base_path"])
except:
print("Problem with creating folder")
if "file_prefix" in scanargs and scanargs["file_prefix"] != None:
print(scanargs["file_prefix"])
self.parent.file_prefix.set(scanargs["file_prefix"]).wait()
if "daq_num_points" in scanargs:
d["num_points_total"] = scanargs["daq_num_points"]
@@ -55,13 +72,13 @@ class StdDaqMixin(CustomDeviceMixin):
# Try to figure out number of points
num_points = 1
points_valid = False
if "steps" in scanargs and scanargs['steps'] is not None:
if "steps" in scanargs and scanargs["steps"] is not None:
num_points *= scanargs["steps"]
points_valid = True
if "exp_burst" in scanargs and scanargs['exp_burst'] is not None:
if "exp_burst" in scanargs and scanargs["exp_burst"] is not None:
num_points *= scanargs["exp_burst"]
points_valid = True
if "repeats" in scanargs and scanargs['repeats'] is not None:
if "repeats" in scanargs and scanargs["repeats"] is not None:
num_points *= scanargs["repeats"]
points_valid = True
if points_valid:
@@ -82,19 +99,17 @@ class StdDaqMixin(CustomDeviceMixin):
self._mon.start()
def on_unstage(self):
""" Stop a running acquisition and close connection
"""
"""Stop a running acquisition and close connection"""
print("Creating virtual dataset")
self.parent.create_virtual_dataset()
self.parent.blueunstage()
def on_stop(self):
""" Stop a running acquisition and close connection
"""
"""Stop a running acquisition and close connection"""
self.parent.blueunstage()
def monitor(self) -> None:
""" Monitor status messages while connection is open. This will block the reply monitoring
"""Monitor status messages while connection is open. This will block the reply monitoring
to calling unstage() might throw. Status updates are sent every 1 seconds, but finishing
acquisition means StdDAQ will close connection, so there's no idle state polling.
"""
@@ -103,7 +118,7 @@ class StdDaqMixin(CustomDeviceMixin):
for msg in self.parent._wsclient:
message = json.loads(msg)
self.parent.runstatus.put(message["status"], force=True)
logger.info(f"[{self.parent.name}] Pushed status: {message['status']}")
# logger.info(f"[{self.parent.name}] Pushed status: {message['status']}")
except (ConnectionClosedError, ConnectionClosedOK, AssertionError):
# Libraty throws theese after connection is closed
return
@@ -128,18 +143,31 @@ class StdDaqClient(PSIDeviceBase):
daq = StdDaqClient(name="daq", ws_url="ws://xbl-daq-29:8080", rest_url="http://xbl-daq-29:5000")
```
"""
# pylint: disable=too-many-instance-attributes
custom_prepare_cls = StdDaqMixin
USER_ACCESS = ["set_daq_config", "get_daq_config", "nuke", "connect", "message", "state", "bluestage", "blueunstage"]
USER_ACCESS = [
"set_daq_config",
"get_daq_config",
"nuke",
"connect",
"message",
"state",
"bluestage",
"blueunstage",
]
_wsclient = None
# Status attributes
ws_url = Component(Signal, kind=Kind.config, metadata={'write_access': False})
runstatus = Component(Signal, value="unknown", kind=Kind.normal, metadata={'write_access': False})
ws_url = Component(Signal, kind=Kind.config, metadata={"write_access": False})
runstatus = Component(
Signal, value="unknown", kind=Kind.normal, metadata={"write_access": False}
)
num_images = Component(Signal, value=10000, kind=Kind.config)
file_path = Component(Signal, value="/gpfs/test/test-beamline", kind=Kind.config)
file_prefix = Component(Signal, value="file", kind=Kind.config)
# Configuration attributes
rest_url = Component(Signal, kind=Kind.config, metadata={'write_access': False})
rest_url = Component(Signal, kind=Kind.config, metadata={"write_access": False})
cfg_detector_name = Component(Signal, kind=Kind.config)
cfg_detector_type = Component(Signal, kind=Kind.config)
cfg_bit_depth = Component(Signal, kind=Kind.config)
@@ -159,10 +187,19 @@ class StdDaqClient(PSIDeviceBase):
device_manager=None,
ws_url: str = "ws://localhost:8080",
rest_url: str = "http://localhost:5000",
data_source_name = None,
data_source_name=None,
**kwargs,
) -> None:
super().__init__(prefix=prefix, name=name, kind=kind, read_attrs=read_attrs, configuration_attrs=configuration_attrs, parent=parent, device_manager=device_manager, **kwargs)
super().__init__(
prefix=prefix,
name=name,
kind=kind,
read_attrs=read_attrs,
configuration_attrs=configuration_attrs,
parent=parent,
device_manager=device_manager,
**kwargs,
)
self.ws_url.set(ws_url, force=True).wait()
self.rest_url.set(rest_url, force=True).wait()
self.data_source_name = data_source_name
@@ -245,53 +282,52 @@ class StdDaqClient(PSIDeviceBase):
nr_writers: int, optional
Number of writers [int].
"""
# Configuration parameters
if 'image_width' in d and d['image_width']!=None:
self.cfg_pixel_width.set(d['image_width']).wait()
if 'image_height' in d and d['image_height']!=None:
self.cfg_pixel_height.set(d['image_height']).wait()
if 'bit_depth' in d:
self.cfg_bit_depth.set(d['bit_depth']).wait()
if 'nr_writers' in d and d['nr_writers']!=None:
self.cfg_nr_writers.set(d['nr_writers']).wait()
if "image_width" in d and d["image_width"] != None:
self.cfg_pixel_width.set(d["image_width"]).wait()
if "image_height" in d and d["image_height"] != None:
self.cfg_pixel_height.set(d["image_height"]).wait()
if "bit_depth" in d:
self.cfg_bit_depth.set(d["bit_depth"]).wait()
if "nr_writers" in d and d["nr_writers"] != None:
self.cfg_nr_writers.set(d["nr_writers"]).wait()
# Run parameters
if 'num_points_total' in d:
self.num_images.set(d['num_points_total']).wait()
if 'file_path' in d and d['file_path']!=None:
self.file_path.set(d['file_path']).wait()
if "num_points_total" in d:
self.num_images.set(d["num_points_total"]).wait()
# Restart the DAQ if resolution changed
cfg = self.get_daq_config()
if cfg['image_pixel_height'] != self.cfg_pixel_height.get() or \
cfg['image_pixel_width'] != self.cfg_pixel_width.get() or \
cfg['bit_depth'] != self.cfg_bit_depth.get() or \
cfg['number_of_writers'] != self.cfg_nr_writers.get():
if (
cfg["image_pixel_height"] != self.cfg_pixel_height.get()
or cfg["image_pixel_width"] != self.cfg_pixel_width.get()
or cfg["bit_depth"] != self.cfg_bit_depth.get()
or cfg["number_of_writers"] != self.cfg_nr_writers.get()
):
# Stop if current status is not idle
if self.state() != "idle":
raise RuntimeWarning(f"[{self.name}] stdDAQ reconfiguration might corrupt files")
logger.warning(f"[{self.name}] stdDAQ reconfiguration might corrupt files")
# Update retrieved config
cfg['image_pixel_height'] = int(self.cfg_pixel_height.get())
cfg['image_pixel_width'] = int(self.cfg_pixel_width.get())
cfg['bit_depth'] = int(self.cfg_bit_depth.get())
cfg['number_of_writers'] = int(self.cfg_nr_writers.get())
cfg["image_pixel_height"] = int(self.cfg_pixel_height.get())
cfg["image_pixel_width"] = int(self.cfg_pixel_width.get())
cfg["bit_depth"] = int(self.cfg_bit_depth.get())
cfg["number_of_writers"] = int(self.cfg_nr_writers.get())
self.set_daq_config(cfg)
sleep(1)
self.get_daq_config(update=True)
def bluestage(self):
""" Stages the stdDAQ
"""Stages the stdDAQ
Opens a new connection to the stdDAQ, sends the start command with
the current configuration. It waits for the first reply and checks
it for obvious failures.
Opens a new connection to the stdDAQ, sends the start command with
the current configuration. It waits for the first reply and checks
it for obvious failures.
"""
# Can't stage into a running exposure
print('Before')
if self.state() != 'idle':
if self.state() != "idle":
raise RuntimeError(f"[{self.name}] stdDAQ can't stage from state: {self.state()}")
print('After')
# Must make sure that image size matches the data source
if self.data_source_name is not None:
@@ -301,17 +337,27 @@ class StdDaqClient(PSIDeviceBase):
daq_img_h = self.cfg_pixel_height.get()
if not (daq_img_w == cam_img_w and daq_img_h == cam_img_h):
raise RuntimeError(f"[{self.name}] stdDAQ image resolution ({daq_img_w} , {daq_img_h}) does not match camera with ({cam_img_w} , {cam_img_h})")
raise RuntimeError(
f"[{self.name}] stdDAQ image resolution ({daq_img_w} , {daq_img_h}) does not match camera with ({cam_img_w} , {cam_img_h})"
)
else:
logger.warning(f"[{self.name}] stdDAQ image resolution ({daq_img_w} , {daq_img_h}) matches camera with ({cam_img_w} , {cam_img_h})")
logger.warning(
f"[{self.name}] stdDAQ image resolution ({daq_img_w} , {daq_img_h}) matches camera with ({cam_img_w} , {cam_img_h})"
)
file_path = self.file_path.get()
num_images = self.num_images.get()
file_prefix = self.file_prefix.get()
print(file_prefix)
# New connection
self._wsclient = self.connect()
message = {"command": "start", "path": file_path, "n_image": num_images, }
message = {
"command": "start",
"path": file_path,
"file_prefix": file_prefix,
"n_image": num_images,
}
reply = self.message(message)
if reply is not None:
@@ -322,8 +368,10 @@ class StdDaqClient(PSIDeviceBase):
# Give it more time to reconfigure
if reply["status"] in ("rejected"):
# FIXME: running exposure is a nogo
if reply['reason'] == "driver is busy!":
raise RuntimeError(f"[{self.name}] Start stdDAQ command rejected: already running")
if reply["reason"] == "driver is busy!":
raise RuntimeError(
f"[{self.name}] Start stdDAQ command rejected: already running"
)
else:
# Give it more time to consolidate
sleep(1)
@@ -332,16 +380,18 @@ class StdDaqClient(PSIDeviceBase):
print(f"[{self.name}] Started stdDAQ in: {reply['status']}")
return
raise RuntimeError(f"[{self.name}] Failed to start the stdDAQ in 1 tries, reason: {reply['reason']}")
raise RuntimeError(
f"[{self.name}] Failed to start the stdDAQ in 1 tries, reason: {reply['reason']}"
)
def blueunstage(self):
""" Unstages the stdDAQ
"""Unstages the stdDAQ
Opens a new connection to the stdDAQ, sends the stop command and
waits for the idle state.
Opens a new connection to the stdDAQ, sends the stop command and
waits for the idle state.
"""
ii = 0
while ii<10:
while ii < 10:
# Stop the DAQ (will close connection) - reply is always "success"
self._wsclient = self.connect()
self.message({"command": "stop_all"}, wait_reply=False)
@@ -355,7 +405,7 @@ class StdDaqClient(PSIDeviceBase):
if reply is not None:
logger.info(f"[{self.name}] DAQ status reply: {reply}")
reply = json.loads(reply)
if reply["status"] in ("idle", "error"):
# Only 'idle' state accepted
print(f"DAQ stopped on try {ii}")
@@ -372,6 +422,7 @@ class StdDaqClient(PSIDeviceBase):
# Bluesky flyer interface
def complete(self) -> SubscriptionStatus:
"""Wait for current run. Must end in status 'file_saved'."""
def is_running(*args, value, timestamp, **kwargs):
result = value in ["idle", "file_saved", "error"]
return result
@@ -380,40 +431,35 @@ class StdDaqClient(PSIDeviceBase):
return status
def get_daq_config(self, update=False) -> dict:
"""Read the current configuration from the DAQ
"""
r = requests.get(
self.rest_url.get() + '/api/config/get',
params={'user': "ioc"},
timeout=2)
"""Read the current configuration from the DAQ"""
r = requests.get(self.rest_url.get() + "/api/config/get", params={"user": "ioc"}, timeout=2)
if r.status_code != 200:
raise ConnectionError(f"[{self.name}] Error {r.status_code}:\t{r.text}")
cfg = r.json()
if update:
self.cfg_detector_name.set(cfg['detector_name']).wait()
self.cfg_detector_type.set(cfg['detector_type']).wait()
self.cfg_bit_depth.set(cfg['bit_depth']).wait()
self.cfg_pixel_height.set(cfg['image_pixel_height']).wait()
self.cfg_pixel_width.set(cfg['image_pixel_width']).wait()
self.cfg_nr_writers.set(cfg['number_of_writers']).wait()
self.cfg_detector_name.set(cfg["detector_name"]).wait()
self.cfg_detector_type.set(cfg["detector_type"]).wait()
self.cfg_bit_depth.set(cfg["bit_depth"]).wait()
self.cfg_pixel_height.set(cfg["image_pixel_height"]).wait()
self.cfg_pixel_width.set(cfg["image_pixel_width"]).wait()
self.cfg_nr_writers.set(cfg["number_of_writers"]).wait()
return cfg
def set_daq_config(self, config, settle_time=1):
"""Write a full configuration to the DAQ
"""
url = self.rest_url.get() + '/api/config/set'
"""Write a full configuration to the DAQ"""
url = self.rest_url.get() + "/api/config/set"
r = requests.post(
url,
params={"user": "ioc"},
json=config,
timeout=2,
headers={"Content-Type": "application/json"}
)
url,
params={"user": "ioc"},
json=config,
timeout=2,
headers={"Content-Type": "application/json"},
)
if r.status_code != 200:
raise ConnectionError(f"[{self.name}] Error {r.status_code}:\t{r.text}")
# Wait for service to restart (and connect to make sure)
sleep(settle_time)
# sleep(settle_time)
self.connect()
return r.json()
@@ -421,21 +467,24 @@ class StdDaqClient(PSIDeviceBase):
"""Combine the stddaq written files in a given folder in an interleaved
h5 virtual dataset
"""
url = self.rest_url.get() + '/api/h5/create_interleaved_vds'
url = self.rest_url.get() + "/api/h5/create_interleaved_vds"
file_path = self.file_path.get()
file_prefix = self.file_prefix.get()
r = requests.post(
url,
params = {'user': 'ioc'},
data = {'base_path': file_path, 'output_file': 'fede_virtual_test'},
timeout = 2,
headers = {'Content-type': 'application/json'}
params={"user": "ioc"},
json={
"base_path": file_path,
"file_prefix": file_prefix,
"output_file": file_prefix.rstrip("_") + ".h5",
},
timeout=2,
headers={"Content-type": "application/json"},
)
print(r)
print(file_path)
def nuke(self, restarttime=5):
""" Reconfigures the stdDAQ to restart the services. This causes
"""Reconfigures the stdDAQ to restart the services. This causes
systemd to kill the current DAQ service and restart it with the same
configuration. Which might corrupt the currently written file...
"""
@@ -444,18 +493,20 @@ class StdDaqClient(PSIDeviceBase):
sleep(restarttime)
def state(self) -> str | None:
""" Querry the current system status"""
"""Querry the current system status"""
try:
wsclient = self.connect()
wsclient.send(json.dumps({'command': 'status'}))
wsclient.send(json.dumps({"command": "status"}))
r = wsclient.recv(timeout=1)
r = json.loads(r)
return r['status']
return r["status"]
except ConnectionRefusedError:
raise
# Automatically connect to microXAS testbench if directly invoked
if __name__ == "__main__":
daq = StdDaqClient(name="daq", ws_url="ws://sls-daq-001:8080", rest_url="http://sls-daq-001:5000")
daq = StdDaqClient(
name="daq", ws_url="ws://sls-daq-001:8080", rest_url="http://sls-daq-001:5000"
)
daq.wait_for_connection()

View File

@@ -1,2 +1,2 @@
from .tutorial_fly_scan import AcquireDark, AcquireFlat, TutorialFlyScanContLine
from .tutorial_fly_scan import AcquireDark, AcquireWhite, AcquireRefs, TutorialFlyScanContLine
from .tomcat_scans import TomcatStepScan, TomcatSnapNStep, TomcatSimpleSequence

View File

@@ -97,7 +97,7 @@ class TomcatStepScan(ScanBase):
yield from self._move_scan_motors_and_wait(pos)
time.sleep(self.settling_time)
trigger_time = self.exp_time * self.burst_at_each_point
trigger_time = 0.001*self.exp_time * self.burst_at_each_point
yield from self.stubs.trigger(min_wait=trigger_time)
# yield from self.stubs.trigger(group='trigger', point_id=self.point_id)
# time.sleep(trigger_time)

View File

@@ -4,7 +4,6 @@ import numpy as np
from bec_lib.device import DeviceBase
from bec_server.scan_server.scans import Acquire, AsyncFlyScanBase
class AcquireDark(Acquire):
scan_name = "acquire_dark"
required_kwargs = ["exp_burst"]
@@ -28,7 +27,7 @@ class AcquireDark(Acquire):
image_height : int, optional
ROI size in the y-direction [pixels]
acq_mode : str, optional
Predefined acquisition mode (default=)
Predefined acquisition mode (default= 'default')
file_path : str, optional
File path for standard daq
@@ -52,40 +51,249 @@ class AcquireDark(Acquire):
yield from super().scan_core()
class AcquireFlat(Acquire):
scan_name = "acquire_flat"
required_kwargs = ["num"]
gui_config = {"Acquisition parameters": ["num"]}
class AcquireWhite(Acquire):
scan_name = "acquire_white"
required_kwargs = ["exp_burst", "sample_position_out", "sample_angle_out"]
gui_config = {"Acquisition parameters": ["exp_burst"]}
def __init__(self, num: int, out_position: float, **kwargs):
def __init__(self, exp_burst: int, sample_position_out: float, sample_angle_out: float, **kwargs):
"""
Acquire a flat field image. This scan is used to acquire a flat field image. The flat field image is an image taken
with the shutter open but the sample out of the beam. The flat field image is used to correct the data images for
Acquire flat field images. This scan is used to acquire flat field images. The flat field image is an image taken
with the shutter open but the sample out of the beam. Flat field images are used to correct the data images for
non-uniformity in the detector.
Args:
num (int): number of flat field images to acquire
out_position (float): position to move the sample stage to take the flat field image
exp_burst : int
Number of flat field images to acquire (no default)
sample_position_out : float
Position to move the sample stage to position the sample out of beam and take flat field images
sample_angle_out : float
Angular position where to take the flat field images
exp_time : float, optional
Exposure time [ms]. If not specified, the currently configured value on the camera will be used
exp_period : float, optional
Exposure period [ms]. If not specified, the currently configured value on the camera will be used
image_width : int, optional
ROI size in the x-direction [pixels]. If not specified, the currently configured value on the camera will be used
image_height : int, optional
ROI size in the y-direction [pixels]. If not specified, the currently configured value on the camera will be used
acq_mode : str, optional
Predefined acquisition mode (default= 'default')
file_path : str, optional
File path for standard daq
Returns:
ScanReport
Examples:
>>> scans.acquire_flat(5, 20)
>>> scans.acquire_white(5, 20)
"""
super().__init__(**kwargs)
self.burst_at_each_point = num
self.out_position = out_position
self.sample_stage = "samy" # change to the correct sample stage device
self.shutter = "hx" # change to the correct shutter device
self.burst_at_each_point = 1
self.sample_position_out = sample_position_out
self.sample_angle_out = sample_angle_out
self.scan_motors = ["eyex", "eyez", "es1_roty"] # change to the correct shutter device
self.dark_shutter_pos_out = 1 ### change with a variable
self.dark_shutter_pos_in = 0 ### change with a variable
def scan_core(self):
# open the shutter and move the sample stage to the out position
yield from self.stubs.set_and_wait(
device=[self.shutter, self.sample_stage], positions=[1, self.out_position]
)
self.scan_motors = ["eyez", "es1_roty"] # change to the correct shutter device
yield from self._move_scan_motors_and_wait([self.sample_position_out, self.sample_angle_out])
self.scan_motors = ["eyex"] # change to the correct shutter device
yield from self._move_scan_motors_and_wait([self.dark_shutter_pos_out])
# TODO add opening of fast shutter
yield from super().scan_core()
# TODO add closing of fast shutter
yield from self._move_scan_motors_and_wait([self.dark_shutter_pos_in])
class AcquireProjectins(Acquire):
scan_name = "acquire_projections"
required_kwargs = ["exp_burst", "sample_position_in", "start_position", "angular_range"]
gui_config = {"Acquisition parameters": ["exp_burst"]}
def __init__(self,
exp_burst: int,
sample_position_in: float,
start_position: float,
angular_range: float,
**kwargs):
"""
Acquire projection images.
Args:
exp_burst : int
Number of flat field images to acquire (no default)
sample_position_in : float
Position to move the sample stage to position the sample in the beam
start_position : float
Angular start position for the scan
angular_range : float
Angular range
exp_time : float, optional
Exposure time [ms]. If not specified, the currently configured value on the camera will be used
exp_period : float, optional
Exposure period [ms]. If not specified, the currently configured value on the camera will be used
image_width : int, optional
ROI size in the x-direction [pixels]. If not specified, the currently configured value on the camera will be used
image_height : int, optional
ROI size in the y-direction [pixels]. If not specified, the currently configured value on the camera will be used
acq_mode : str, optional
Predefined acquisition mode (default= 'default')
file_path : str, optional
File path for standard daq
Returns:
ScanReport
Examples:
>>> scans.acquire_white(5, 20)
"""
super().__init__(**kwargs)
self.burst_at_each_point = 1
self.sample_position_in = sample_position_in
self.start_position = start_position
self.angular_range = angular_range
self.scan_motors = ["eyex", "eyez", "es1_roty"] # change to the correct shutter device
self.dark_shutter_pos_out = 1 ### change with a variable
self.dark_shutter_pos_in = 0 ### change with a variable
def scan_core(self):
# open the shutter and move the sample stage to the out position
self.scan_motors = ["eyez", "es1_roty"] # change to the correct shutter device
yield from self._move_scan_motors_and_wait([self.sample_position_out, self.sample_angle_out])
self.scan_motors = ["eyex"] # change to the correct shutter device
yield from self._move_scan_motors_and_wait([self.dark_shutter_pos_out])
# TODO add opening of fast shutter
yield from super().scan_core()
# TODO add closing of fast shutter
yield from self._move_scan_motors_and_wait([self.dark_shutter_pos_in])
class AcquireRefs(Acquire):
scan_name = "acquire_refs"
required_kwargs = []
gui_config = {}
def __init__(
self,
num_darks: int = 0,
num_flats: int = 0,
sample_angle_out: float = 0,
sample_position_in: float = 0,
sample_position_out: float = 5000,
file_prefix_dark: str = 'tmp_dark',
file_prefix_white: str = 'tmp_white',
exp_time: float = 0,
exp_period: float = 0,
image_width: int = 2016,
image_height: int = 2016,
acq_mode: str = 'default',
file_path: str = 'tmp',
nr_writers: int = 2,
base_path: str = 'tmp',
**kwargs
):
"""
Acquire reference images (darks + whites) and return to beam position.
Reference images are acquired automatically in an optimized sequence and
the sample is returned to the sample_in_position afterwards.
Args:
num_darks : int , optional
Number of dark field images to acquire
num_flats : int , optional
Number of white field images to acquire
sample_position_in : float , optional
Sample stage X position for sample in beam [um]
sample_position_out : float ,optional
Sample stage X position for sample out of the beam [um]
sample_angle_out : float , optional
Angular position where to take the flat field images
exp_time : float, optional
Exposure time [ms]. If not specified, the currently configured value on the camera will be used
exp_period : float, optional
Exposure period [ms]. If not specified, the currently configured value on the camera will be used
image_width : int, optional
ROI size in the x-direction [pixels]. If not specified, the currently configured value on the camera will be used
image_height : int, optional
ROI size in the y-direction [pixels]. If not specified, the currently configured value on the camera will be used
acq_mode : str, optional
Predefined acquisition mode (default= 'default')
file_path : str, optional
File path for standard daq
Returns:
ScanReport
Examples:
>>> scans.acquire_refs(sample_angle_out=90, sample_position_in=10, num_darks=5, num_flats=5, exp_time=0.1)
"""
super().__init__(**kwargs)
self.sample_position_in = sample_position_in
self.sample_position_out = sample_position_out
self.sample_angle_out = sample_angle_out
self.num_darks = num_darks
self.num_flats = num_flats
self.file_prefix_dark = file_prefix_dark
self.file_prefix_white = file_prefix_white
self.exp_time = exp_time
self.exp_period = exp_period
self.image_width = image_width
self.image_height = image_height
self.acq_mode = acq_mode
self.file_path = file_path
self.nr_writers = nr_writers
self.base_path = base_path
def scan_core(self):
## TODO move sample in position and do not wait
## TODO move angle in position and do not wait
if self.num_darks:
self.connector.send_client_info(
f"Acquiring {self.num_darks} dark images",
show_asap=True,
rid=self.metadata.get("RID"),
)
darks = AcquireDark(
exp_burst=self.num_darks,
file_prefix=self.file_prefix_dark,
device_manager=self.device_manager,
metadata=self.metadata
)
yield from darks.scan_core()
self.point_id = darks.point_id
if self.num_flats:
self.connector.send_client_info(
f"Acquiring {self.num_flats} flat field images",
show_asap=True,
rid=self.metadata.get("RID"),
)
flats = AcquireWhite(
exp_burst=self.num_flats,
sample_position_out=self.sample_position_out,
sample_angle_out=self.sample_angle_out,
file_prefix=self.file_prefix_white,
device_manager=self.device_manager,
metadata=self.metadata,
)
flats.point_id = self.point_id
yield from flats.scan_core()
self.point_id = flats.point_id
## TODO move sample in beam and do not wait
## TODO move rotation to angle and do not wait
class TutorialFlyScanContLine(AsyncFlyScanBase):
@@ -169,7 +377,7 @@ class TutorialFlyScanContLine(AsyncFlyScanBase):
show_asap=True,
rid=self.metadata.get("RID"),
)
flats = AcquireFlat(
flats = AcquireWhite(
num=self.num_flats,
exp_time=self.exp_time,
out_position=self.sample_out,

View File

@@ -18,6 +18,25 @@ def dev_disable_all():
dev[k].enabled = False
def cam_select(camera: str):
"""Select the active camera pipeline"""
if isinstance(camera, str):
if camera in ("gf", "gf2", "gigafrost"):
dev.gfcam.enabled = True
dev.gfdaq.enabled = True
dev.daq_stream0.enabled = True
dev.pcocam.enabled = False
dev.pcodaq.enabled = False
dev.pco_stream0.enabled = False
if camera in ("pco", "pco.edge", "pcoedge"):
dev.gfcam.enabled = False
dev.gfdaq.enabled = False
dev.daq_stream0.enabled = False
dev.pcocam.enabled = True
dev.pcodaq.enabled = True
dev.pco_stream0.enabled = True
def anotherstepscan(
scan_start,
@@ -26,8 +45,9 @@ def anotherstepscan(
exp_time=0.005,
exp_burst=5,
settling_time=0,
image_width=2016,
image_height=2016,
camera=None,
image_width=None,
image_height=None,
sync="inp1",
**kwargs
):
@@ -41,31 +61,49 @@ def anotherstepscan(
--------
demostepscan(scan_start=-32, scan_end=148, steps=180, exp_time=0.005, exp_burst=5)
"""
# if not bl_check_beam():
# raise RuntimeError("Beamline is not in ready state")
# Check beamline status before scan
if not bl_check_beam():
raise RuntimeError("Beamline is not in ready state")
# Enable the correct camera before scan
cam_select(camera)
# This scan uses software triggering
if isinstance(camera, str):
if camera in ("gf", "gf2", "gigafrost"):
dev.gfcam.software_trigger = True
if camera in ("pco", "pco.edge", "pcoedge"):
dev.pcocam.software_trigger = True
dev_disable_all()
# Disable aerotech controller
# dev.es1_tasks.enabled = False
# dev.es1_psod.enabled = False
# dev.es1_ddaq.enabled = True
# Enable scan motor
dev.es1_roty.enabled = True
#dev.es1_ddaq.enabled = True
dev.gfcam.enabled = True
dev.gfdaq.enabled = True
dev.daq_stream0.enabled = True
dev.daq_stream1.enabled = False
print("Handing over to 'scans.tomcatstepscan'")
scans.tomcatstepscan(
scan_start=scan_start,
scan_end=scan_end,
steps=steps,
exp_time=exp_time,
exp_burst=exp_burst,
relative=False,
image_width=image_width,
image_height=image_height,
settling_time=settling_time,
sync=sync,
**kwargs
)
try:
scans.tomcatstepscan(
scan_start=scan_start,
scan_end=scan_end,
steps=steps,
exp_time=exp_time,
exp_burst=exp_burst,
relative=False,
image_width=image_width,
image_height=image_height,
settling_time=settling_time,
sync=sync,
**kwargs
)
finally:
# if isinstance(camera, str):
# if camera in ("gf", "gf2", "gigafrost"):
# dev.gfcam.software_trigger = False
# if camera in ("pco", "pco.edge", "pcoedge"):
# dev.pcocam.software_trigger = False
pass
@@ -78,8 +116,9 @@ def anothersequencescan(
repmode="PosNeg",
exp_time=0.005,
exp_burst=180,
image_width=2016,
image_height=2016,
camera=None,
image_width=None,
image_height=None,
sync="pso",
**kwargs
):
@@ -96,16 +135,15 @@ def anothersequencescan(
--------
>>> anothersequencescan(33, 180, 180, exp_time=0.005, exp_frames=1800, repeats=10)
"""
# Check beamline status before scan
if not bl_check_beam():
raise RuntimeError("Beamline is not in ready state")
# Enable the correct camera before scan
cam_select(camera)
# Enabling aerotech controller
dev.es1_tasks.enabled = True
dev.es1_psod.enabled = False
dev.es1_ddaq.enabled = True
dev.gfcam.enabled = True
dev.gfdaq.enabled = True
dev.daq_stream0.enabled = True
dev.daq_stream1.enabled = False
print("Handing over to 'scans.sequencescan'")
scans.tomcatsimplesequencescan(
@@ -131,8 +169,9 @@ def anothersnapnstepscan(
steps,
exp_time=0.005,
exp_burst=180,
image_width=2016,
image_height=2016,
camera=None,
image_width=None,
image_height=None,
settling_time=0.1,
sync="pso",
**kwargs
@@ -148,17 +187,15 @@ def anothersnapnstepscan(
--------
>>> anothersnapnstepscan(33, 180, 180, exp_time=0.005, exp_frames=1800, repeats=10)
"""
# Check beamline status before scan
if not bl_check_beam():
raise RuntimeError("Beamline is not in ready state")
# Enable the correct camera before scan
cam_select(camera)
# Enabling aerotech controller
dev.es1_tasks.enabled = True
dev.es1_psod.enabled = False
dev.es1_ddaq.enabled = True
dev.gfcam.enabled = True
dev.gfdaq.enabled = True
dev.daq_stream0.enabled = True
dev.daq_stream1.enabled = False
print("Handing over to 'scans.tomcatsnapnstepscan'")
scans.tomcatsnapnstepscan(
@@ -174,3 +211,58 @@ def anothersnapnstepscan(
**kwargs
)
def ascan(motor, scan_start, scan_end, steps, exp_time, datasource, visual=True, **kwargs):
"""Demo step scan with plotting
This is a simple user-space demo step scan with automatic plorring and fitting via the BEC.
It's mostly a standard BEC scan, just adds GUI setup and fits a hardcoded LlinearModel at
the end (other models are more picky on the initial parameters).
Example:
--------
ascan(dev.dccm_energy, 12,13, steps=21, exp_time=0.1, datasource=dev.dccm_xbpm)
"""
# Dummy method to check beamline status
if not bl_check_beam():
raise RuntimeError("Beamline is not in ready state")
if visual:
# Get or create scan specific window
window = None
for _, val in bec.gui.windows.items():
if val.title == "CurrentScan":
window = val.widget
window.clear_all()
if window is None:
window = bec.gui.new("CurrentScan")
# Draw a simploe plot in the window
dock = window.add_dock(f"ScanDisplay {motor}")
plt1 = dock.add_widget("BECWaveformWidget")
plt1.plot(x_name=motor, y_name=datasource)
plt1.set_x_label(motor)
plt1.set_y_label(datasource)
plt1.add_dap(motor, datasource, dap="LinearModel")
window.show()
print("Handing over to 'scans.line_scan'")
if "relative" in kwargs:
del kwargs["relative"]
s = scans.line_scan(
motor, scan_start, scan_end, steps=steps, exp_time=exp_time, relative=False, **kwargs
)
if visual:
fit = plt1.get_dap_params()
else:
fit = bec.dap.LinearModel.fit(s, motor.name, motor.name, datasource.name, datasource.name)
# TODO: Move to fitted value... like center, peak, edge, etc...
return s, fit

View File

@@ -4,9 +4,7 @@
def bl_check_beam():
"""Checks beamline status"""
motor_enabled = bool(dev.es1_roty.motor_enable.get())
result = motor_enabled
return result
return True
def demostepscan(

View File

@@ -8,35 +8,73 @@ class Measurement:
def __init__(self):
self.sample_name = 'tmp'
self.data_path = 'disk_test'
bec.system_config.file_suffix = None
bec.system_config.file_directory = os.path.join(self.data_path,self.sample_name)
self.nimages = 1000
self.nimages_dark = 50
self.nimages_white = 100
self.start_angle = 0
self.sample_angle_out = 0
self.sample_position_in = 0
self.sample_position_out = 1
# To be able to keep what is already set on the camera
self.exposure_time = None
self.exposure_period = None
self.roix = None
self.roiy = None
bec.system_config.file_suffix = self.sample_name
bec.system_config.file_directory = os.path.join(self.data_path,self.sample_name)
self.build_filename()
def build_filename(self):
"""
Build and set filename for bec and stddaq
"""
bec.system_config.file_suffix = self.sample_name
bec.system_config.file_directory = os.path.join(self.data_path,self.sample_name)
self.file_path = '/data/test/test-beamline/test_fede'
if os.path.isdir(self.file_path):
pass
self.get_available_detectors()
self.get_enabled_detectors()
if len(self.enabled_detectors) > 1:
print('WARNING! More than 1 detector enabled')
self.show_enabled_detectors()
elif len(self.enabled_detectors) == 0:
print("WARNING! No detector enabled!!")
self.show_available_detectors()
else:
os.mkdir(self.file_path)
self.show_enabled_detectors()
self.det = self.enabled_detectors[0]
self.device_name = self.enabled_detectors[0].name
self.build_filename()
self.exposure_time = self.det.cfgExposure.get()
self.exposure_period = self.det.cfgFramerate.get()
self.roix = self.det.cfgRoiX.get()
self.roiy = self.det.cfgRoiY.get()
def build_filename(self, acquisition_type='data'):
"""
Build and set filepath for bec
Build filepath and file prefix for stddaq
acquisition_type : string, optional
Type of images: a choice between dark, white, or data (default = data)
"""
if acquisition_type != "data" and acquisition_type != "dark" and acquisition_type != "white":
print("WARNING: chosen acquisition type not permitted! \n")
print("The chosen acquitisition type as been set to \"data\"!")
acquisition_type == "data"
self.scan_sample_name = 'S' + str(bec.queue.next_scan_number) + '_' + self.sample_name
# File path for bec
bec.system_config.file_directory = os.path.join(self.data_path,self.sample_name,self.scan_sample_name)
# File path for stddaq (for now root folders different between console and stddaq server)
self.file_path = os.path.join('/data/test/test-beamline',bec.system_config.file_directory, '_device_dat', self.device_name) # _device_dat does not work for now.
# A hack for now to create the right permissions
self.base_path = os.path.join('/data/test/test-beamline',self.data_path)
self.file_prefix = self.scan_sample_name + '_' + self.device_name + '_' + acquisition_type + '_'
def configure(self,sample_name=None, data_path=None, exposure_time=None,
exposure_period=None, roix=None, roiy=None,nimages=None,
nimages_dark=None, nimages_white=None):
nimages_dark=None, nimages_white=None,
start_angle=None, sample_angle_out=None,
sample_position_in=None, sample_position_out=None):
"""
Reconfigure the measurement with any number of new parameter
@@ -44,24 +82,34 @@ class Measurement:
----------
sample_name : string, optional
Name of the sample or measurement. This name will be used to construct
the name of the measurement directory (default=None)
the name of the measurement directory (default = None)
data_path : string, optional
Information used to build the data directory for the measurement
(default=None)
(default = None)
exposure_time : float, optional
Exposure time [ms] (default=None)
Exposure time [ms] (default = None)
exposure_period : float, optional
Exposure period [ms] (default=None)
Exposure period [ms] (default = None)
roix : int, optional
ROI size in the x-direction [pixels] (default=None)
ROI size in the x-direction [pixels] (default = None)
roiy : int, optional
ROI size in the y-direction [pixels] (default=None)
ROI size in the y-direction [pixels] (default = None)
nimages : int, optional
Number of images to acquire (default=None)
Number of images to acquire (default = None)
nimages_dark : int, optional
Number of dark images to acquire (default=None)
Number of dark images to acquire (default = None)
nimages_white : int, optional
Number of white images to acquire (default=None)
Number of white images to acquire (default = None)
start_angle : float, optional
The start angle for the scan [deg] (default = None)
sample_angle_out : float, optional
Sample rotation angle for sample out of the beam [deg]
(default = None)
sample_position_in : float, optional
Sample stage X position for sample in beam [um] (default = None)
sample_position_out : float, optional
Sample stage X position for sample out of the beam [um]
(default = None)
"""
if sample_name != None:
@@ -82,17 +130,157 @@ class Measurement:
self.roix = roix
if roiy != None:
self.roiy = roiy
if start_angle != None:
self.start_angle = start_angle
if sample_angle_out != None:
self.sample_angle_out = sample_angle_out
if sample_position_in != None:
self.sample_position_in = sample_position_in
if sample_position_out != None:
self.sample_position_out = sample_position_out
self.build_filename()
def disable_detector(self, detector_name):
"""
Disable detector
"""
def acquire_darks(self,nimages_dark, exposure_time=None, exposure_period=None,
roix=None, roiy=None, acq_mode=None, file_path=None):
if detector_name not in self.available_detectors_names:
print("WARNING! The detector " + str(detector_name + " is not available!"))
print("You can check the available detectors with the command dev.show_all()")
devices_to_be_disabled = [obj for obj in dev.get_devices_with_tags(detector_name)]
for i in range(len(devices_to_be_disabled)):
devices_to_be_disabled[i].enabled = False
self.get_enabled_detectors()
if len(self.enabled_detectors) > 1:
print('WARNING! More than 1 detector enabled')
self.show_enabled_detectors()
elif len(self.enabled_detectors) == 0:
print("WARNING! No detector enabled!!")
self.show_available_detectors()
else:
self.show_enabled_detectors()
self.det = self.enabled_detectors[0]
self.device_name = self.enabled_detectors[0].name
self.build_filename()
def enable_detector(self, detector_name):
"""
Enable detector
"""
if detector_name not in self.available_detectors_names:
print("WARNING! The detector " + str(detector_name + " is not available!"))
print("You can check the available detectors with the command dev.show_all()")
devices_to_be_enabled = [obj for obj in dev.get_devices_with_tags(detector_name)]
for i in range(len(devices_to_be_enabled)):
devices_to_be_enabled[i].enabled = True
dev.daq_stream1.enabled = False
self.get_enabled_detectors()
if len(self.enabled_detectors) > 1:
print('WARNING! More than 1 detector enabled')
self.show_enabled_detectors()
elif len(self.enabled_detectors) == 0:
print("WARNING! No detector enabled!!")
self.show_available_detectors()
else:
self.show_enabled_detectors()
self.det = self.enabled_detectors[0]
self.device_name = self.enabled_detectors[0].name
self.build_filename()
def get_available_detectors(self):
"""
Check available detectors
"""
self.available_detectors = [obj for obj in dev.get_devices_with_tags('camera')]
self.available_detectors_names = []
for i in range(len(self.available_detectors)):
self.available_detectors_names.append(self.available_detectors[i].name)
def get_enabled_detectors(self):
"""
Get enabled detectors
"""
self.enabled_detectors = [obj for obj in dev.get_devices_with_tags('camera') if obj.enabled]
def show_available_detectors(self):
"""
Show available detectors
"""
print("Available detectors:")
for i in range(len(self.available_detectors)):
print(self.available_detectors[i].name + '\tenabled ' + str(self.available_detectors[i].enabled))
def show_enabled_detectors(self):
"""
List enabled detectors
"""
print("Enabled detectors:")
for i in range(len(self.enabled_detectors)):
print(self.enabled_detectors[i].name)
def show_all(self):
"""
Show configuration
TODO: make it work for multiple devices
"""
print("Sample name: " + self.sample_name)
print("Data path: " + self.data_path)
print("Number of images: " + str(self.nimages))
print("Number of darks: " + str(self.nimages_dark))
print("Number of flats: " + str(self.nimages_white))
if self.exposure_time == None:
print("Exposure time: " + str(self.det.cfgExposure.get()))
self.exposure_time = self.det.cfgExposure.get()
else:
print("Exposure time: " + str(self.exposure_time))
if self.exposure_period == None:
print("Exposure period: " + str(self.det.cfgFramerate.get()))
self.exposure_period = self.det.cfgFramerate.get()
else:
print("Exposure period: " + str(self.exposure_period))
if self.roix == None:
print("Roix: " + str(self.det.cfgRoiX.get()))
self.roix = self.det.cfgRoiX.get()
else:
print("Roix: " + str(self.roix))
if self.roiy == None:
print("Roiy: " + str(self.det.cfgRoiY.get()))
self.roiy = self.det.cfgRoiY.get()
else:
print("Roiy: " + str(self.roiy))
print("Start angle: " + str(self.start_angle))
print("Sample angle out: " + str(self.sample_angle_out))
print("Sample position in: " + str(self.sample_position_in))
print("Sample position out: " + str(self.sample_position_out))
def acquire_darks(self,nimages_dark=None, exposure_time=None, exposure_period=None,
roix=None, roiy=None, acq_mode=None):
"""
Acquire a set of dark images with shutters closed.
Parameters
----------
nimages_dark : int
nimages_dark : int, optional
Number of dark images to acquire (no default)
exposure_time : float, optional
Exposure time [ms]. If not specified, the currently configured value on the camera will be used
@@ -104,44 +292,14 @@ class Measurement:
ROI size in the y-direction [pixels]
acq_mode : str, optional
Predefined acquisition mode (default=None)
file_path : str, optional
File path for standard daq (default=None)
Example:
--------
fede_darks(100, exposure_time=5)
m.acquire_darks(nimages_darks=100, exposure_time=5)
"""
# dev.es1_tasks.enabled = False
# dev.es1_psod.enabled = False
# dev.es1_ddaq.enabled = False
# dev.es1_ismc.enabled = False
# dev.es1_roty.enabled = False
dev.gfcam.enabled = True
dev.gfdaq.enabled = True
dev.daq_stream0.enabled = True
dev.daq_stream1.enabled = False
dev.gfcam.cfgAcqMode.set(1).wait()
dev.gfcam.cmdSetParam.set(1).wait()
dev.gfcam.cfgEnableExt.set(0).wait()
dev.gfcam.cfgEnableSoft.set(0).wait()
dev.gfcam.cfgEnableAlways.set(1).wait()
dev.gfcam.cfgTrigExt.set(0).wait()
dev.gfcam.cfgTrigSoft.set(0).wait()
dev.gfcam.cfgTrigTimer.set(0).wait()
dev.gfcam.cfgTrigAuto.set(1).wait()
dev.gfcam.cfgExpExt.set(0).wait()
dev.gfcam.cfgExpSoft.set(0).wait()
dev.gfcam.cfgExpTimer.set(1).wait()
dev.gfcam.cfgCntStartBit.set(0).wait()
# Commit changes to GF
dev.gfcam.cmdSetParam.set(1).wait()
if nimages_dark != None:
self.nimages_dark = nimages_dark
if exposure_time != None:
self.exposure_time = exposure_time
if exposure_period != None:
@@ -150,14 +308,137 @@ class Measurement:
self.roix = roix
if roiy != None:
self.roiy = roiy
if file_path!=None:
if os.path.isdir(file_path):
pass
else:
os.mkdir(file_path)
self.build_filename(acquisition_type='dark')
### TODO: camera reset
print("Handing over to 'scans.acquire_dark")
scans.acquire_dark(exp_burst=nimages_dark, exp_time=self.exposure_time, exp_period=self.exposure_period, image_width=self.roix,
image_height=self.roiy, acq_mode=acq_mode, file_path=file_path, nr_writers=2)
scans.acquire_dark(exp_burst=self.nimages_dark, exp_time=self.exposure_time, exp_period=self.exposure_period, image_width=self.roix,
image_height=self.roiy, acq_mode=acq_mode, file_path=self.file_path, nr_writers=2, base_path=self.base_path,
file_prefix=self.file_prefix)
def acquire_whites(self,nimages_white=None, sample_angle_out=None, sample_position_out=None,
exposure_time=None, exposure_period=None,
roix=None, roiy=None, acq_mode=None):
"""
Acquire a set of whites images with shutters open and sample out of beam.
Parameters
----------
nimages_whites : int, optional
Number of white images to acquire (no default)
sample_angle_out : float, optional
Sample rotation angle for sample out of the beam [deg]
sample_position_out : float, optional
Sample stage X position for sample out of the beam [um]
exposure_time : float, optional
Exposure time [ms]. If not specified, the currently configured value on the camera will be used
exposure_period : float, optional
Exposure period [ms]
roix : int, optional
ROI size in the x-direction [pixels]
roiy : int, optional
ROI size in the y-direction [pixels]
acq_mode : str, optional
Predefined acquisition mode (default=None)
Example:
--------
m.acquire_whites(nimages_whites=100, exposure_time=5)
"""
if nimages_white != None:
self.nimages_white = nimages_white
if sample_angle_out != None:
self.sample_angle_out = sample_angle_out
if sample_position_out != None:
self.sample_position_out = sample_position_out
if exposure_time != None:
self.exposure_time = exposure_time
if exposure_period != None:
self.exposure_period = exposure_period
if roix != None:
self.roix = roix
if roiy != None:
self.roiy = roiy
self.build_filename(acquisition_type='white')
### TODO: camera reset
print("Handing over to 'scans.acquire_whites")
scans.acquire_white(exp_burst=self.nimages_white, sample_angle_out=self.sample_angle_out, sample_position_out= self.sample_position_out,
exp_time=self.exposure_time, exp_period=self.exposure_period, image_width=self.roix,
image_height=self.roiy, acq_mode=acq_mode, file_path=self.file_path, nr_writers=2, base_path=self.base_path,
file_prefix=self.file_prefix)
def acquire_refs(self,nimages_dark=None, nimages_white=None, sample_angle_out=None,
sample_position_in=None, sample_position_out=None,
exposure_time=None, exposure_period=None,
roix=None, roiy=None, acq_mode=None):
"""
Acquire reference images (darks + whites) and return to beam position.
Reference images are acquired automatically in an optimized sequence and
the sample is returned to the sample_in_position afterwards.
Parameters
----------
darks : int, optional
Number of dark images to acquire (no default)
nimages_whites : int, optional
Number of white images to acquire (no default)
sample_angle_out : float, optional
Sample rotation angle for sample out of the beam [deg]
sample_position_in : float, optional
Sample stage X position for sample in of the beam [um]
sample_position_out : float, optional
Sample stage X position for sample out of the beam [um]
exposure_time : float, optional
Exposure time [ms]. If not specified, the currently configured value on the camera will be used
exposure_period : float, optional
Exposure period [ms]
roix : int, optional
ROI size in the x-direction [pixels]
roiy : int, optional
ROI size in the y-direction [pixels]
acq_mode : str, optional
Predefined acquisition mode (default=None)
Example:
--------
m.acquire_refs(nimages_whites=100, exposure_time=5)
"""
if nimages_dark != None:
self.nimages_dark = nimages_dark
if nimages_white != None:
self.nimages_white = nimages_white
if sample_angle_out != None:
self.sample_angle_out = sample_angle_out
if sample_position_in != None:
self.sample_position_in = sample_position_in
if sample_position_out != None:
self.sample_position_out = sample_position_out
if exposure_time != None:
self.exposure_time = exposure_time
if exposure_period != None:
self.exposure_period = exposure_period
if roix != None:
self.roix = roix
if roiy != None:
self.roiy = roiy
self.build_filename(acquisition_type='dark')
file_prefix_dark = self.file_prefix
self.build_filename(acquisition_type='white')
file_prefix_white = self.file_prefix
### TODO: camera reset
print("Handing over to 'scans.acquire_refs")
scans.acquire_refs(num_darks=self.nimages_dark, num_flats=self.nimages_white, sample_angle_out=self.sample_angle_out,
sample_position_in=self.sample_position_in, sample_position_out=self.sample_position_out,
exp_time=self.exposure_time, exp_period=self.exposure_period, image_width=self.roix,
image_height=self.roiy, acq_mode='default', file_path=self.file_path, nr_writers=2, base_path=self.base_path,
file_prefix_dark=file_prefix_dark, file_prefix_white=file_prefix_white)