Compare commits

..

19 Commits

Author SHA1 Message Date
d81587646e merge from developer on commit b6db097800 to properly clear udp destination in fpga for jungfrau mainly 2022-09-02 09:57:11 +02:00
5508f0135d merge fix 2022-03-21 11:08:02 +01:00
f2b8aa9dbd Merge branch 'developer' into rr_rxr 2022-03-21 10:56:41 +01:00
e554099bd9 binaries in 2022-03-21 10:34:09 +01:00
001fcf03d9 merge fix 2022-03-21 10:32:49 +01:00
1c6369a5a8 binaries in 2021-11-26 11:57:53 +01:00
4012f139ec merge fix from 6.1.0 2021-11-26 10:59:23 +01:00
630b7cd539 fixed 2021-10-26 15:35:56 +02:00
3ebb3e7508 wip 2021-10-25 17:22:50 +02:00
a1c4eb6d05 wip 2021-10-25 12:33:02 +02:00
b9b5c623ec rx_hostname, port, port2, dstlist works 2021-10-25 11:10:12 +02:00
41dc8329ab first try on setrxhostname 2021-10-22 17:15:04 +02:00
c3499c0b93 Merge branch 'developer' into rr_rxr 2021-10-22 16:12:04 +02:00
578528eb59 merge fix 2021-10-19 14:54:39 +02:00
0658d1c843 merge fix 2021-10-08 09:50:36 +02:00
ce6dc589c8 merge fix 2021-09-30 16:07:30 +02:00
0b45fdfed8 merge fix 2021-09-28 16:09:51 +02:00
9217d9f22c Merge branch 'developer' into rr_rxr 2021-09-15 11:41:29 +02:00
7d4e2470a3 hacky version compiles 2021-09-13 15:45:46 +02:00
66 changed files with 3079 additions and 2887 deletions

View File

@ -47,18 +47,10 @@ This document describes the differences between v7.0.0 and v6.x.x
- stop servers also check for errors at startup( in case it was running with an older version) - stop servers also check for errors at startup( in case it was running with an older version)
- hostname cmd failed when connecting to servers in update mode (ctb, moench, jungfrau, eiger) - hostname cmd failed when connecting to servers in update mode (ctb, moench, jungfrau, eiger)
- missingpackets signed (negative => extra packets) - missingpackets signed (negative => extra packets)
- framescaught and frameindex now returns a vector for each port
- progress looks at activated or enabled ports, so progress does not stagnate
- (eiger) disable datastreaming also for virtual servers only for 10g
- missing packets also takes care of disabled ports
- added geometry to metadata - added geometry to metadata
- 10g eiger nextframenumber get fixed. - 10g eiger nextframenumber get fixed.
- stop, able to set nextframenumber to a consistent (max + 1) for all modules if different (eiger/ctb/jungfrau/moench) - stop, able to set nextframenumber to a consistent (max + 1) for all modules if different (eiger/ctb/jungfrau/moench)
- ctb: can set names for all the dacs
- fpga/kernel programming, checks if drive is a special file and not a normal file
- gotthard 25 um image reconstructed in gui and virtual hdf5 (firmware updated for slave to reverse channels)
- master binary file in json format now
- fixed bug introduced in 6.0.0: hdf5 files created 1 file per frame after the initial file which had maxframesperfile
2. Resolved Issues 2. Resolved Issues
================== ==================

View File

@ -0,0 +1,12 @@
hostname bchip258+
0:rx_hostname pc13784:1954+pc13784:1955+
udp_srcip 10.0.2.184
udp_dstip 10.0.2.1
0:0 udp_dstport 50000
0:1 udp_dstport 50001
#0:0 udp_dstlist port=50001
#0:1 udp_dstlist port=50002

View File

@ -1,45 +1,43 @@
# SPDX-License-Identifier: LGPL-3.0-or-other # SPDX-License-Identifier: LGPL-3.0-or-other
# Copyright (C) 2021 Contributors to the SLS Detector Package # Copyright (C) 2021 Contributors to the SLS Detector Package
from .detector import Detector, freeze from .detector import Detector
from .utils import element_if_equal from .utils import element_if_equal
from .dacs import DetectorDacs, NamedDacs from .dacs import DetectorDacs
import _slsdet import _slsdet
dacIndex = _slsdet.slsDetectorDefs.dacIndex dacIndex = _slsdet.slsDetectorDefs.dacIndex
from .detector_property import DetectorProperty from .detector_property import DetectorProperty
# class CtbDacs(DetectorDacs): class CtbDacs(DetectorDacs):
# """ """
# Ctb dacs Ctb dacs
# """ """
# _dacs = [('dac0', dacIndex(0), 0, 4000, 1400), _dacs = [('dac0', dacIndex(0), 0, 4000, 1400),
# ('dac1', dacIndex(1), 0, 4000, 1200), ('dac1', dacIndex(1), 0, 4000, 1200),
# ('dac2', dacIndex(2), 0, 4000, 900), ('dac2', dacIndex(2), 0, 4000, 900),
# ('dac3', dacIndex(3), 0, 4000, 1050), ('dac3', dacIndex(3), 0, 4000, 1050),
# ('dac4', dacIndex(4), 0, 4000, 1400), ('dac4', dacIndex(4), 0, 4000, 1400),
# ('dac5', dacIndex(5), 0, 4000, 655), ('dac5', dacIndex(5), 0, 4000, 655),
# ('dac6', dacIndex(6), 0, 4000, 2000), ('dac6', dacIndex(6), 0, 4000, 2000),
# ('dac7', dacIndex(7), 0, 4000, 1400), ('dac7', dacIndex(7), 0, 4000, 1400),
# ('dac8', dacIndex(8), 0, 4000, 850), ('dac8', dacIndex(8), 0, 4000, 850),
# ('dac9', dacIndex(9), 0, 4000, 2000), ('dac9', dacIndex(9), 0, 4000, 2000),
# ('dac10', dacIndex(10), 0, 4000, 2294), ('dac10', dacIndex(10), 0, 4000, 2294),
# ('dac11', dacIndex(11), 0, 4000, 983), ('dac11', dacIndex(11), 0, 4000, 983),
# ('dac12', dacIndex(12), 0, 4000, 1475), ('dac12', dacIndex(12), 0, 4000, 1475),
# ('dac13', dacIndex(13), 0, 4000, 1200), ('dac13', dacIndex(13), 0, 4000, 1200),
# ('dac14', dacIndex(14), 0, 4000, 1600), ('dac14', dacIndex(14), 0, 4000, 1600),
# ('dac15', dacIndex(15), 0, 4000, 1455), ('dac15', dacIndex(15), 0, 4000, 1455),
# ('dac16', dacIndex(16), 0, 4000, 0), ('dac16', dacIndex(16), 0, 4000, 0),
# ('dac17', dacIndex(17), 0, 4000, 1000), ('dac17', dacIndex(17), 0, 4000, 1000),
# ] ]
# _dacnames = [_d[0] for _d in _dacs] _dacnames = [_d[0] for _d in _dacs]
from .utils import element from .utils import element
@freeze
class Ctb(Detector): class Ctb(Detector):
def __init__(self, id = 0): def __init__(self, id = 0):
super().__init__(id) super().__init__(id)
self._frozen = False self._frozen = False
# self._dacs = CtbDacs(self) self._dacs = CtbDacs(self)
self._dacs = NamedDacs(self)
@property @property
def dacs(self): def dacs(self):

View File

@ -36,79 +36,6 @@ class Dac(DetectorProperty):
dacstr = ''.join([f'{item:5d}' for item in self.get()]) dacstr = ''.join([f'{item:5d}' for item in self.get()])
return f'{self.__name__:15s}:{dacstr}' return f'{self.__name__:15s}:{dacstr}'
class NamedDacs:
"""
New implementation of the detector dacs. Used at the momen for
Ctb but should replace the old one for all detectors
"""
_frozen = False
_direct_access = ['_detector', '_current', '_dacnames']
def __init__(self, detector):
self._detector = detector
self._current = 0
self._dacnames = [n.replace(" ", "") for n in detector.getDacNames()]
# # Populate the dacs
for i,name in enumerate(self._dacnames):
#name, enum, low, high, default, detector
setattr(self, name, Dac(name, dacIndex(i), 0, 4000, 1000, detector))
self._frozen = True
# def __getattr__(self, name):
# return self.__getattribute__('_' + name)
def __setattr__(self, name, value):
if not self._frozen:
#durining init we need to be able to set up the class
super().__setattr__(name, value)
else:
#Later we restrict us to manipulate dacs and a few fields
if name in self._direct_access:
super().__setattr__(name, value)
elif name in self._dacnames:
return self.__getattribute__(name).__setitem__(slice(None, None, None), value)
else:
raise AttributeError(f'Dac not found: {name}')
def __next__(self):
if self._current >= len(self._dacnames):
self._current = 0
raise StopIteration
else:
self._current += 1
return self.__getattribute__(self._dacnames[self._current-1])
# return self.__getattr__(self._dacnames[self._current-1])
def __iter__(self):
return self
def __repr__(self):
r_str = ['========== DACS =========']
r_str += [repr(dac) for dac in self]
return '\n'.join(r_str)
def get_asarray(self):
"""
Read the dacs into a numpy array with dimensions [ndacs, nmodules]
"""
dac_array = np.zeros((len(self._dacnames), len(self._detector)))
for i, _d in enumerate(self):
dac_array[i,:] = _d[:]
return dac_array
def to_array(self):
return self.get_asarray()
def set_from_array(self, dac_array):
"""
Set the dacs from an numpy array with dac values. [ndacs, nmodules]
"""
dac_array = dac_array.astype(np.int)
for i, _d in enumerate(self):
_d[:] = dac_array[i]
def from_array(self, dac_array):
self.set_from_array(dac_array)
class DetectorDacs: class DetectorDacs:
_dacs = [] _dacs = []
@ -123,7 +50,7 @@ class DetectorDacs:
# Index to support iteration # Index to support iteration
self._current = 0 self._current = 0
# Name the attributes? # Populate the dacs
for _d in self._dacs: for _d in self._dacs:
setattr(self, '_'+_d[0], Dac(*_d, detector)) setattr(self, '_'+_d[0], Dac(*_d, detector))
@ -132,9 +59,6 @@ class DetectorDacs:
def __getattr__(self, name): def __getattr__(self, name):
return self.__getattribute__('_' + name) return self.__getattribute__('_' + name)
@property
def dacnames(self):
return [_d[0] for _d in _dacs]
def __setattr__(self, name, value): def __setattr__(self, name, value):
if name in self._dacnames: if name in self._dacnames:

View File

@ -599,7 +599,7 @@ class Detector(CppDetectorApi):
@property @property
@element @element
def rx_framescaught(self): def rx_framescaught(self):
"""Number of frames caught by each port in receiver.""" """Number of frames caught by receiver."""
return self.getFramesCaught() return self.getFramesCaught()
@property @property
@ -1571,16 +1571,8 @@ class Detector(CppDetectorApi):
@property @property
def daclist(self): def daclist(self):
""" """Gets the list of enums for every dac for this detector."""
List of enums for every dac for this detector. return self.getDacList()
:setter: Only implemented for Chiptestboard
"""
return self.getDacNames()
@daclist.setter
def daclist(self, value):
self.setDacNames(value)
@property @property
def dacvalues(self): def dacvalues(self):
@ -1926,7 +1918,7 @@ class Detector(CppDetectorApi):
@property @property
@element @element
def rx_frameindex(self): def rx_frameindex(self):
"""Current frame index received for each port in receiver during acquisition.""" """Current frame index received in receiver during acquisition."""
return self.getRxCurrentFrameIndex() return self.getRxCurrentFrameIndex()
@property @property

View File

@ -493,17 +493,13 @@ void init_det(py::module &m) {
Detector::getReceiverStatus, Detector::getReceiverStatus,
py::arg() = Positions{}) py::arg() = Positions{})
.def("getFramesCaught", .def("getFramesCaught",
(Result<std::vector<int64_t>>(Detector::*)(sls::Positions) const) & (Result<int64_t>(Detector::*)(sls::Positions) const) &
Detector::getFramesCaught, Detector::getFramesCaught,
py::arg() = Positions{}) py::arg() = Positions{})
.def("getNumMissingPackets", .def("getNumMissingPackets",
(Result<std::vector<int64_t>>(Detector::*)(sls::Positions) const) & (Result<std::vector<int64_t>>(Detector::*)(sls::Positions) const) &
Detector::getNumMissingPackets, Detector::getNumMissingPackets,
py::arg() = Positions{}) py::arg() = Positions{})
.def("getRxCurrentFrameIndex",
(Result<std::vector<int64_t>>(Detector::*)(sls::Positions) const) &
Detector::getRxCurrentFrameIndex,
py::arg() = Positions{})
.def("getNextFrameNumber", .def("getNextFrameNumber",
(Result<uint64_t>(Detector::*)(sls::Positions) const) & (Result<uint64_t>(Detector::*)(sls::Positions) const) &
Detector::getNextFrameNumber, Detector::getNextFrameNumber,
@ -1427,19 +1423,6 @@ void init_det(py::module &m) {
(void (Detector::*)(bool, sls::Positions)) & (void (Detector::*)(bool, sls::Positions)) &
Detector::setLEDEnable, Detector::setLEDEnable,
py::arg(), py::arg() = Positions{}) py::arg(), py::arg() = Positions{})
.def("setDacNames",
(void (Detector::*)(const std::vector<std::string>)) &
Detector::setDacNames,
py::arg())
.def("getDacNames", (std::vector<std::string>(Detector::*)() const) &
Detector::getDacNames)
.def("getDacIndex",
(defs::dacIndex(Detector::*)(const std::string &)) &
Detector::getDacIndex,
py::arg())
.def("getDacName",
(std::string(Detector::*)(defs::dacIndex)) & Detector::getDacName,
py::arg())
.def("setPattern", .def("setPattern",
(void (Detector::*)(const std::string &, sls::Positions)) & (void (Detector::*)(const std::string &, sls::Positions)) &
Detector::setPattern, Detector::setPattern,
@ -1544,10 +1527,9 @@ void init_det(py::module &m) {
Detector::setAdditionalJsonParameter, Detector::setAdditionalJsonParameter,
py::arg(), py::arg(), py::arg() = Positions{}) py::arg(), py::arg(), py::arg() = Positions{})
.def("programFPGA", .def("programFPGA",
(void (Detector::*)(const std::string &, const bool, (void (Detector::*)(const std::string &, sls::Positions)) &
sls::Positions)) &
Detector::programFPGA, Detector::programFPGA,
py::arg(), py::arg(), py::arg() = Positions{}) py::arg(), py::arg() = Positions{})
.def("resetFPGA", .def("resetFPGA",
(void (Detector::*)(sls::Positions)) & Detector::resetFPGA, (void (Detector::*)(sls::Positions)) & Detector::resetFPGA,
py::arg() = Positions{}) py::arg() = Positions{})
@ -1674,5 +1656,9 @@ void init_det(py::module &m) {
Detector::getMeasurementTime, Detector::getMeasurementTime,
py::arg() = Positions{}) py::arg() = Positions{})
.def("getUserDetails", .def("getUserDetails",
(std::string(Detector::*)() const) & Detector::getUserDetails); (std::string(Detector::*)() const) & Detector::getUserDetails)
.def("getRxCurrentFrameIndex",
(Result<uint64_t>(Detector::*)(sls::Positions) const) &
Detector::getRxCurrentFrameIndex,
py::arg() = Positions{});
} }

View File

@ -429,15 +429,10 @@ class singlePhotonDetector : public analogDetector<uint16_t> {
for (ic = -(clusterSize / 2); ic < (clusterSize / 2) + 1; for (ic = -(clusterSize / 2); ic < (clusterSize / 2) + 1;
ic++) { ic++) {
if ((iy + ir) >= 0 && (iy + ir) < ny && if ((iy + ir) >= iy && (iy + ir) < ny &&
(ix + ic) >= 0 && (ix + ic) < nx) { (ix + ic) >= ix && (ix + ic) < nx) {
if ((iy + ir) >= iy && (ix + ic) >= ix ) {
val[(iy + ir) * nx + ix + ic] = val[(iy + ir) * nx + ix + ic] =
subtractPedestal(data, ix + ic, iy + ir, cm); subtractPedestal(data, ix + ic, iy + ir, cm);
}
v = &(val[(iy + ir) * nx + ix + ic]); v = &(val[(iy + ir) * nx + ix + ic]);
tot += *v; tot += *v;
if (ir <= 0 && ic <= 0) if (ir <= 0 && ic <= 0)
@ -448,9 +443,9 @@ class singlePhotonDetector : public analogDetector<uint16_t> {
tl += *v; tl += *v;
if (ir >= 0 && ic >= 0) if (ir >= 0 && ic >= 0)
tr += *v; tr += *v;
if (*v > max) //{ if (*v > max) {
max = *v; max = *v;
//} }
} }
} }
} }
@ -518,19 +513,12 @@ class singlePhotonDetector : public analogDetector<uint16_t> {
for (ic = -(clusterSize / 2); for (ic = -(clusterSize / 2);
ic < (clusterSize / 2) + 1; ic++) { ic < (clusterSize / 2) + 1; ic++) {
if ((iy + ir) >= 0 && (iy + ir) < ny && if ((iy + ir) >= 0 && (iy + ir) < ny &&
(ix + ic) >= 0 && (ix + ic) < nx) { (ix + ic) >= 0 && (ix + ic) < nx)
(clusters + nph) (clusters + nph)
->set_data(val[(iy + ir) * nx + ix + ic], ->set_data(val[(iy + ir) * nx + ix + ic],
ic, ir); ic, ir);
if (val[(iy + ir) * nx + ix + ic]>max)
good=0;
} }
} }
}
if (good==0) {
(clusters + nph)->print();
cout << max << " " << val[iy * nx + ix] << endl;
}
good = 1; good = 1;
if (eMin > 0 && tot < eMin) if (eMin > 0 && tot < eMin)
good = 0; good = 0;

View File

@ -216,18 +216,14 @@ class single_photon_hit {
// int ix, iy; // int ix, iy;
printf("***************\n");
printf("** %d %d **\n",x,y);
for (int iy = 0; iy < dy; iy++) { for (int iy = 0; iy < dy; iy++) {
for (int ix = 0; ix < dx; ix++) { for (int ix = 0; ix < dx; ix++) {
printf("%d \t", data[ix + iy * dx]); printf("%d \t", data[ix + iy * dx]);
} }
printf("\n"); printf("\n");
} }
printf("***************\n");
} }
/** /**
assign the value to the element of the cluster matrix, with relative assign the value to the element of the cluster matrix, with relative
coordinates where the center of the cluster is (0,0) \param v value to be coordinates where the center of the cluster is (0,0) \param v value to be

View File

@ -91,10 +91,8 @@ class qDrawPlot : public QWidget, private Ui::PlotObject {
void Update2dPlot(); void Update2dPlot();
void Update1dXYRange(); void Update1dXYRange();
void Update2dXYRange(); void Update2dXYRange();
void rearrangeGotthard25data(double *data);
static const int NUM_PEDESTAL_FRAMES = 20; static const int NUM_PEDESTAL_FRAMES = 20;
static const int NUM_GOTTHARD25_CHANS = 1280;
sls::Detector *det; sls::Detector *det;
slsDetectorDefs::detectorType detType; slsDetectorDefs::detectorType detType;
@ -166,5 +164,4 @@ class qDrawPlot : public QWidget, private Ui::PlotObject {
uint32_t pixelMask{0}; uint32_t pixelMask{0};
uint32_t gainMask{0}; uint32_t gainMask{0};
int gainOffset{0}; int gainOffset{0};
bool gotthard25;
}; };

View File

@ -80,10 +80,6 @@ void qDrawPlot::SetupWidgetWindow() {
fileSaveName = "Image"; fileSaveName = "Image";
} }
gotthard25 = ((detType == slsDetectorDefs::GOTTHARD2 ||
detType == slsDetectorDefs::GOTTHARD) &&
det->size() == 2);
SetupPlots(); SetupPlots();
SetDataCallBack(true); SetDataCallBack(true);
det->registerAcquisitionFinishedCallback(&(GetAcquisitionFinishedCallBack), det->registerAcquisitionFinishedCallback(&(GetAcquisitionFinishedCallBack),
@ -811,11 +807,6 @@ void qDrawPlot::GetData(detectorData *data, uint64_t frameIndex,
isGainDataExtracted = false; isGainDataExtracted = false;
} }
// gotthard25um rearranging
if (gotthard25) {
rearrangeGotthard25data(rawData);
}
// title and frame index titles // title and frame index titles
plotTitle = plotTitle =
plotTitlePrefix + QString(data->fileName.c_str()).section('/', -1); plotTitlePrefix + QString(data->fileName.c_str()).section('/', -1);
@ -1154,18 +1145,6 @@ void qDrawPlot::toDoublePixelData(double *dest, char *source, int size,
} }
} }
void qDrawPlot::rearrangeGotthard25data(double *data) {
const int nChans = NUM_GOTTHARD25_CHANS;
double temp[nChans * 2] = {0.0};
for (int i = 0; i != nChans; ++i) {
// master module
temp[i * 2] = data[i];
// slave module
temp[i * 2 + 1] = data[nChans + i];
}
memcpy(data, temp, nChans * 2 * sizeof(double));
}
void qDrawPlot::UpdatePlot() { void qDrawPlot::UpdatePlot() {
std::lock_guard<std::mutex> lock(mPlots); std::lock_guard<std::mutex> lock(mPlots);
LOG(logDEBUG) << "Update Plot"; LOG(logDEBUG) << "Update Plot";

View File

@ -2448,17 +2448,15 @@ void *start_timer(void *arg) {
} }
int skipData = 0; int skipData = 0;
int tgEnable = send_to_ten_gig;
if (!eiger_virtual_activate || if (!eiger_virtual_activate ||
(tgEnable && (!eiger_virtual_left_datastream && !eiger_virtual_right_datastream)) {
(!eiger_virtual_left_datastream && !eiger_virtual_right_datastream))) {
skipData = 1; skipData = 1;
LOG(logWARNING, ("Not sending Left and Right datastream\n")); LOG(logWARNING, ("Not sending Left and Right datastream\n"));
} }
if (tgEnable && !eiger_virtual_left_datastream) { if (!eiger_virtual_left_datastream) {
LOG(logWARNING, ("Not sending Left datastream\n")); LOG(logWARNING, ("Not sending Left datastream\n"));
} }
if (tgEnable && !eiger_virtual_right_datastream) { if (!eiger_virtual_right_datastream) {
LOG(logWARNING, ("Not sending Right datastream\n")); LOG(logWARNING, ("Not sending Right datastream\n"));
} }
@ -2468,6 +2466,7 @@ void *start_timer(void *arg) {
int dr = eiger_dynamicrange; int dr = eiger_dynamicrange;
double bytesPerPixel = (double)dr / 8.00; double bytesPerPixel = (double)dr / 8.00;
int tgEnable = send_to_ten_gig;
int datasize = (tgEnable ? 4096 : 1024); int datasize = (tgEnable ? 4096 : 1024);
int packetsize = datasize + sizeof(sls_detector_header); int packetsize = datasize + sizeof(sls_detector_header);
int maxPacketsPerFrame = (tgEnable ? 4 : 16) * dr; int maxPacketsPerFrame = (tgEnable ? 4 : 16) * dr;
@ -2673,16 +2672,14 @@ void *start_timer(void *arg) {
} }
} }
} }
if ((!tgEnable || if (eiger_virtual_left_datastream && i >= startval &&
(tgEnable && eiger_virtual_left_datastream)) && i <= endval) {
i >= startval && i <= endval) {
usleep(eiger_virtual_transmission_delay_left); usleep(eiger_virtual_transmission_delay_left);
sendUDPPacket(iRxEntry, 0, packetData, packetsize); sendUDPPacket(iRxEntry, 0, packetData, packetsize);
LOG(logDEBUG1, ("Sent left packet: %d\n", i)); LOG(logDEBUG1, ("Sent left packet: %d\n", i));
} }
if ((!tgEnable || if (eiger_virtual_right_datastream && i >= startval &&
(tgEnable && eiger_virtual_right_datastream)) && i <= endval) {
i >= startval && i <= endval) {
usleep(eiger_virtual_transmission_delay_right); usleep(eiger_virtual_transmission_delay_right);
sendUDPPacket(iRxEntry, 1, packetData2, packetsize); sendUDPPacket(iRxEntry, 1, packetData2, packetsize);
LOG(logDEBUG1, ("Sent right packet: %d\n", i)); LOG(logDEBUG1, ("Sent right packet: %d\n", i));

View File

@ -1603,7 +1603,7 @@ void setTiming(enum timingMode arg) {
int master = 0; int master = 0;
isMaster(&master); isMaster(&master);
if (!master && arg == AUTO_TIMING) if (master && arg == AUTO_TIMING)
arg = TRIGGER_EXPOSURE; arg = TRIGGER_EXPOSURE;
uint32_t addr = CONFIG_REG; uint32_t addr = CONFIG_REG;

View File

@ -26,12 +26,10 @@ int preparetoCopyProgram(char *mess, char *functionType, FILE **fd,
uint64_t fsize); uint64_t fsize);
int eraseAndWriteToFlash(char *mess, enum PROGRAM_INDEX index, int eraseAndWriteToFlash(char *mess, enum PROGRAM_INDEX index,
char *functionType, char *clientChecksum, char *functionType, char *clientChecksum,
ssize_t fsize, int forceDeleteNormalFile); ssize_t fsize);
int getDrive(char *mess, enum PROGRAM_INDEX index); int getDrive(char *mess, enum PROGRAM_INDEX index);
/** Notify fpga not to touch flash, open src and flash drive to write */ /** Notify fpga not to touch flash, open src and flash drive to write */
int openFileForFlash(char *mess, enum PROGRAM_INDEX index, FILE **flashfd, FILE **srcfd, int openFileForFlash(char *mess, FILE **flashfd, FILE **srcfd);
int forceDeleteNormalFile);
int checkNormalFile(char *mess, enum PROGRAM_INDEX index, int forceDeleteNormalFile);
int eraseFlash(char *mess); int eraseFlash(char *mess);
/* write from tmp file to flash */ /* write from tmp file to flash */
int writeToFlash(char *mess, ssize_t fsize, FILE *flashfd, FILE *srcfd); int writeToFlash(char *mess, ssize_t fsize, FILE *flashfd, FILE *srcfd);

View File

@ -285,8 +285,7 @@ int update_detector_server(int);
int receive_program(int file_des, enum PROGRAM_INDEX index); int receive_program(int file_des, enum PROGRAM_INDEX index);
void receive_program_via_blackfin(int file_des, enum PROGRAM_INDEX index, void receive_program_via_blackfin(int file_des, enum PROGRAM_INDEX index,
char *functionType, uint64_t filesize, char *functionType, uint64_t filesize,
char *checksum, char *serverName, char *checksum, char *serverName);
int forceDeleteNormalFile);
void receive_program_default(int file_des, enum PROGRAM_INDEX index, void receive_program_default(int file_des, enum PROGRAM_INDEX index,
char *functionType, uint64_t filesize, char *functionType, uint64_t filesize,
char *checksum, char *serverName); char *checksum, char *serverName);

View File

@ -7,7 +7,6 @@
#include "slsDetectorServer_defs.h" #include "slsDetectorServer_defs.h"
#include <string.h> #include <string.h>
#include <sys/stat.h>
#include <sys/sysinfo.h> #include <sys/sysinfo.h>
#include <unistd.h> // usleep #include <unistd.h> // usleep
@ -39,9 +38,6 @@
#define CMD_GET_AMD_FLASH "dmesg | grep Amd" #define CMD_GET_AMD_FLASH "dmesg | grep Amd"
#define CMD_CREATE_DEVICE_FILE_PART1 "mknod"
#define CMD_CREATE_DEVICE_FILE_PART2 "c 90 6"
#define FLASH_BUFFER_MEMORY_SIZE (128 * 1024) // 500 KB #define FLASH_BUFFER_MEMORY_SIZE (128 * 1024) // 500 KB
// clang-format on // clang-format on
@ -278,8 +274,7 @@ int allowUpdate(char *mess, char *functionType) {
getKernelVersion(retvals); getKernelVersion(retvals);
snprintf(mess, MAX_STR_LENGTH, snprintf(mess, MAX_STR_LENGTH,
"Could not update %s. Kernel version %s is too old to " "Could not update %s. Kernel version %s is too old to "
"update the Amd flash/ root directory. Most likely, blackfin " "update the Amd flash/ root directory. Most likely, blackfin needs rescue or replacement. Please contact us.\n",
"needs rescue or replacement. Please contact us.\n",
functionType, retvals); functionType, retvals);
LOG(logERROR, (mess)); LOG(logERROR, (mess));
return FAIL; return FAIL;
@ -324,7 +319,7 @@ int preparetoCopyProgram(char *mess, char *functionType, FILE **fd,
int eraseAndWriteToFlash(char *mess, enum PROGRAM_INDEX index, int eraseAndWriteToFlash(char *mess, enum PROGRAM_INDEX index,
char *functionType, char *clientChecksum, char *functionType, char *clientChecksum,
ssize_t fsize, int forceDeleteNormalFile) { ssize_t fsize) {
memset(messageType, 0, sizeof(messageType)); memset(messageType, 0, sizeof(messageType));
strcpy(messageType, functionType); strcpy(messageType, functionType);
@ -335,8 +330,7 @@ int eraseAndWriteToFlash(char *mess, enum PROGRAM_INDEX index,
FILE *flashfd = NULL; FILE *flashfd = NULL;
FILE *srcfd = NULL; FILE *srcfd = NULL;
if (openFileForFlash(mess, index, &flashfd, &srcfd, forceDeleteNormalFile) == if (openFileForFlash(mess, &flashfd, &srcfd) == FAIL) {
FAIL) {
return FAIL; return FAIL;
} }
@ -440,8 +434,7 @@ int getDrive(char *mess, enum PROGRAM_INDEX index) {
return OK; return OK;
} }
int openFileForFlash(char *mess, enum PROGRAM_INDEX index, FILE **flashfd, FILE **srcfd, int openFileForFlash(char *mess, FILE **flashfd, FILE **srcfd) {
int forceDeleteNormalFile) {
// open src file // open src file
*srcfd = fopen(TEMP_PROG_FILE_NAME, "r"); *srcfd = fopen(TEMP_PROG_FILE_NAME, "r");
if (*srcfd == NULL) { if (*srcfd == NULL) {
@ -454,11 +447,6 @@ int openFileForFlash(char *mess, enum PROGRAM_INDEX index, FILE **flashfd, FILE
} }
LOG(logDEBUG1, ("Temp file ready for reading\n")); LOG(logDEBUG1, ("Temp file ready for reading\n"));
if (checkNormalFile(mess, index, forceDeleteNormalFile) == FAIL) {
fclose(*srcfd);
return FAIL;
}
// open flash drive for writing // open flash drive for writing
*flashfd = fopen(flashDriveName, "w"); *flashfd = fopen(flashDriveName, "w");
if (*flashfd == NULL) { if (*flashfd == NULL) {
@ -474,95 +462,6 @@ int openFileForFlash(char *mess, enum PROGRAM_INDEX index, FILE **flashfd, FILE
return OK; return OK;
} }
int checkNormalFile(char *mess, enum PROGRAM_INDEX index, int forceDeleteNormalFile) {
#ifndef VIRTUAL
// check if its a normal file or special file
struct stat buf;
if (stat(flashDriveName, &buf) == -1) {
sprintf(mess,
"Could not %s. Unable to find the flash drive %s\n",
messageType, flashDriveName);
LOG(logERROR, (mess));
return FAIL;
}
// zero = normal file (not char special drive file)
if (!S_ISCHR(buf.st_mode)) {
// kernel memory is not permanent
if (index != PROGRAM_FPGA) {
sprintf(mess,
"Could not %s. The flash drive found is a normal file. "
"Reboot board using 'rebootcontroller' command to load "
"proper device tree\n",
messageType);
LOG(logERROR, (mess));
return FAIL;
}
// user does not allow to fix it (default)
if (forceDeleteNormalFile == 0) {
sprintf(mess,
"Could not %s. The flash drive %s found for fpga programming is a normal file. To "
"fix this (by deleting this file, creating the flash drive and proceeding with "
"programming), re-run the programming command 'programfpga' with parameter "
"'--force-delete-normal-file'\n",
messageType, flashDriveName);
LOG(logERROR, (mess));
return FAIL;
}
// fpga memory stays after a reboot, user allowed to fix it
LOG(logWARNING, ("Flash drive invalidated (normal file). Fixing it...\n"));
// user allows to fix it, so force delete normal file
char cmd[MAX_STR_LENGTH] = {0};
char retvals[MAX_STR_LENGTH] = {0};
if (snprintf(cmd, MAX_STR_LENGTH, "rm %s", flashDriveName) >=
MAX_STR_LENGTH) {
sprintf(mess,
"Could not update %s. Command to delete normal file %s is "
"too long\n",
messageType, flashDriveName);
LOG(logERROR, (mess));
return FAIL;
}
if (executeCommand(cmd, retvals, logDEBUG1) == FAIL) {
snprintf(
mess, MAX_STR_LENGTH,
"Could not update %s. (could not delete normal file %s: %s)\n",
messageType, flashDriveName, retvals);
LOG(logERROR, (mess));
return FAIL;
}
LOG(logINFO, ("\tDeleted Normal File (%s)\n", flashDriveName));
// create special drive
if (snprintf(cmd, MAX_STR_LENGTH, "%s %s %s",
CMD_CREATE_DEVICE_FILE_PART1, flashDriveName,
CMD_CREATE_DEVICE_FILE_PART2) >= MAX_STR_LENGTH) {
sprintf(mess,
"Could not update %s. Command to create special file %s is "
"too long\n",
messageType, flashDriveName);
LOG(logERROR, (mess));
return FAIL;
}
if (executeCommand(cmd, retvals, logDEBUG1) == FAIL) {
snprintf(
mess, MAX_STR_LENGTH,
"Could not update %s. (could not create special file %s: %s)\n",
messageType, flashDriveName, retvals);
LOG(logERROR, (mess));
return FAIL;
}
LOG(logINFO, ("\tSpecial File created (%s)\n", flashDriveName));
} else {
LOG(logINFO, ("\tValidated flash drive (not a normal file)\n"));
}
#endif
return OK;
}
int eraseFlash(char *mess) { int eraseFlash(char *mess) {
LOG(logINFO, ("\tErasing Flash...\n")); LOG(logINFO, ("\tErasing Flash...\n"));

View File

@ -8,7 +8,6 @@
#include <string.h> #include <string.h>
#include <unistd.h> // usleep #include <unistd.h> // usleep
#include <sys/stat.h>
/* global variables */ /* global variables */
@ -147,30 +146,6 @@ int getDrive(char *mess, enum PROGRAM_INDEX index) {
} }
int openFileForFlash(char *mess, FILE **flashfd) { int openFileForFlash(char *mess, FILE **flashfd) {
#ifndef VIRTUAL
// check if its a normal file or special file
struct stat buf;
if (stat(flashDriveName, &buf) == -1) {
sprintf(mess,
"Could not %s. Unable to find the flash drive %s\n",
messageType, flashDriveName);
LOG(logERROR, (mess));
return FAIL;
}
// zero = normal file (not char drive special file)
if (!S_ISCHR(buf.st_mode)) {
// memory is not permanent
sprintf(mess,
"Could not %s. The flash drive found is a normal file. "
"Reboot board using 'rebootcontroller' command to load "
"proper device tree\n",
messageType);
LOG(logERROR, (mess));
return FAIL;
}
LOG(logINFO, ("\tValidated flash drive (not a normal file)\n"));
#endif
*flashfd = fopen(flashDriveName, "w"); *flashfd = fopen(flashDriveName, "w");
if (*flashfd == NULL) { if (*flashfd == NULL) {
sprintf(mess, sprintf(mess,

View File

@ -4003,8 +4003,7 @@ int check_version(int file_des) {
usleep(3 * 1000 * 1000); usleep(3 * 1000 * 1000);
if (!isInitCheckDone()) { if (!isInitCheckDone()) {
ret = FAIL; ret = FAIL;
strcpy(mess, "Server Initialization still not done done in server. " strcpy(mess, "Server Initialization still not done done in server. Unexpected.\n");
"Unexpected.\n");
LOG(logERROR, (mess)); LOG(logERROR, (mess));
} }
} }
@ -9221,8 +9220,25 @@ int clear_all_udp_dst(int file_des) {
if (check_detector_idle("clear all udp destinations") == OK) { if (check_detector_idle("clear all udp destinations") == OK) {
memset(udpDetails, 0, sizeof(udpDetails)); memset(udpDetails, 0, sizeof(udpDetails));
// minimum 1 destination in fpga // minimum 1 destination in fpga
numUdpDestinations = 1; int numdest = 1;
configure_mac(); // set number of destinations
#if defined(JUNGFRAUD) || defined(EIGERD)
if (setNumberofDestinations(numdest) == FAIL) {
ret = FAIL;
strcpy(mess, "Could not clear udp destinations to 1 entry.\n");
LOG(logERROR, (mess));
} else
#endif
{
numUdpDestinations = numdest;
LOG(logINFOBLUE, ("Number of UDP Destinations: %d\n",
numUdpDestinations));
ret = configureMAC();
if (ret == FAIL) {
strcpy(mess, "Could not clear all destinations in the fpga.\n");
LOG(logERROR, (mess));
}
}
} }
} }
return Server_SendResult(file_des, INT32, NULL, 0); return Server_SendResult(file_des, INT32, NULL, 0);
@ -9444,15 +9460,6 @@ int receive_program(int file_des, enum PROGRAM_INDEX index) {
LOG(logINFO, ("\tServer Name: %s\n", serverName)); LOG(logINFO, ("\tServer Name: %s\n", serverName));
} }
#if !defined(GOTTHARD2D) && !defined(MYTHEN3D) && !defined(EIGERD)
int forceDeleteNormalFile = 0;
if (receiveData(file_des, &forceDeleteNormalFile,
sizeof(forceDeleteNormalFile), INT32) < 0)
return printSocketReadError();
LOG(logINFO,
("\tForce Delete Normal File flag? %s\n", (forceDeleteNormalFile ? "Y" : "N")));
#endif
// in same folder as current process (will also work for virtual then // in same folder as current process (will also work for virtual then
// with write permissions) // with write permissions)
{ {
@ -9477,7 +9484,7 @@ int receive_program(int file_des, enum PROGRAM_INDEX index) {
checksum, serverName); checksum, serverName);
#else #else
receive_program_via_blackfin(file_des, index, functionType, receive_program_via_blackfin(file_des, index, functionType,
filesize, checksum, serverName, forceDeleteNormalFile); filesize, checksum, serverName);
#endif #endif
} }
@ -9493,7 +9500,7 @@ int receive_program(int file_des, enum PROGRAM_INDEX index) {
void receive_program_via_blackfin(int file_des, enum PROGRAM_INDEX index, void receive_program_via_blackfin(int file_des, enum PROGRAM_INDEX index,
char *functionType, uint64_t filesize, char *functionType, uint64_t filesize,
char *checksum, char *serverName, int forceDeleteNormalFile) { char *checksum, char *serverName) {
#if !defined(JUNGFRAUD) && !defined(CHIPTESTBOARDD) && !defined(MOENCHD) && \ #if !defined(JUNGFRAUD) && !defined(CHIPTESTBOARDD) && !defined(MOENCHD) && \
!defined(GOTTHARDD) !defined(GOTTHARDD)
@ -9592,7 +9599,7 @@ void receive_program_via_blackfin(int file_des, enum PROGRAM_INDEX index,
case PROGRAM_FPGA: case PROGRAM_FPGA:
case PROGRAM_KERNEL: case PROGRAM_KERNEL:
ret = eraseAndWriteToFlash(mess, index, functionType, checksum, ret = eraseAndWriteToFlash(mess, index, functionType, checksum,
totalsize, forceDeleteNormalFile); totalsize);
break; break;
case PROGRAM_SERVER: case PROGRAM_SERVER:
ret = moveBinaryFile(mess, serverName, TEMP_PROG_FILE_NAME, ret = moveBinaryFile(mess, serverName, TEMP_PROG_FILE_NAME,
@ -9795,16 +9802,12 @@ int set_top(int file_des) {
if (Server_VerifyLock() == OK) { if (Server_VerifyLock() == OK) {
if (arg != 0 && arg != 1) { if (arg != 0 && arg != 1) {
ret = FAIL; ret = FAIL;
sprintf( sprintf(mess, "Could not set top mode. Invalid value: %d. Must be 0 or 1\n", arg);
mess,
"Could not set top mode. Invalid value: %d. Must be 0 or 1\n",
arg);
LOG(logERROR, (mess)); LOG(logERROR, (mess));
} else { } else {
ret = setTop(arg == 1 ? OW_TOP : OW_BOTTOM); ret = setTop(arg == 1 ? OW_TOP : OW_BOTTOM);
if (ret == FAIL) { if (ret == FAIL) {
sprintf(mess, "Could not set %s\n", sprintf(mess, "Could not set %s\n", (arg == 1 ? "Top" : "Bottom"));
(arg == 1 ? "Top" : "Bottom"));
LOG(logERROR, (mess)); LOG(logERROR, (mess));
} else { } else {
int retval = -1; int retval = -1;

View File

@ -7,7 +7,6 @@ set(SOURCES
src/CmdProxy.cpp src/CmdProxy.cpp
src/CmdParser.cpp src/CmdParser.cpp
src/Pattern.cpp src/Pattern.cpp
src/CtbConfig.cpp
) )
add_library(slsDetectorObject OBJECT add_library(slsDetectorObject OBJECT

View File

@ -592,17 +592,12 @@ class Detector {
/** Options: IDLE, TRANSMITTING, RUNNING */ /** Options: IDLE, TRANSMITTING, RUNNING */
Result<defs::runStatus> getReceiverStatus(Positions pos = {}) const; Result<defs::runStatus> getReceiverStatus(Positions pos = {}) const;
/** Gets the number of frames caught for each port in receiver. */ Result<int64_t> getFramesCaught(Positions pos = {}) const;
Result<std::vector<int64_t>> getFramesCaught(Positions pos = {}) const;
/** Gets the number of missing packets for each port in receiver. Negative /** Gets the number of missing packets for each port in receiver. Negative
* number denotes extra packets. */ * number denotes extra packets. */
Result<std::vector<int64_t>> getNumMissingPackets(Positions pos = {}) const; Result<std::vector<int64_t>> getNumMissingPackets(Positions pos = {}) const;
/** Gets frame index for each port in receiver. */
Result<std::vector<int64_t>>
getRxCurrentFrameIndex(Positions pos = {}) const;
/** [Eiger][Jungfrau][Moench][CTB] */ /** [Eiger][Jungfrau][Moench][CTB] */
Result<uint64_t> getNextFrameNumber(Positions pos = {}) const; Result<uint64_t> getNextFrameNumber(Positions pos = {}) const;
@ -704,48 +699,60 @@ class Detector {
/**[Jungfrau] Options 0-31 (or number of udp destinations) */ /**[Jungfrau] Options 0-31 (or number of udp destinations) */
void setFirstUDPDestination(const int value, Positions pos = {}); void setFirstUDPDestination(const int value, Positions pos = {});
Result<IpAddr> getDestinationUDPIP(Positions pos = {}) const; Result<IpAddr> getDestinationUDPIP(Positions pos = {},
const int rx_index = 0) const;
/** IP of the interface in receiver that the detector sends data to */ /** IP of the interface in receiver that the detector sends data to */
void setDestinationUDPIP(const IpAddr ip, Positions pos = {}); void setDestinationUDPIP(const IpAddr ip, Positions pos = {},
const int rx_index = 0);
/** [Jungfrau] bottom half \n [Gotthard2] veto debugging */ /** [Jungfrau] bottom half \n [Gotthard2] veto debugging */
Result<IpAddr> getDestinationUDPIP2(Positions pos = {}) const; Result<IpAddr> getDestinationUDPIP2(Positions pos = {},
const int rx_index = 0) const;
/** [Jungfrau] bottom half \n [Gotthard2] veto debugging */ /** [Jungfrau] bottom half \n [Gotthard2] veto debugging */
void setDestinationUDPIP2(const IpAddr ip, Positions pos = {}); void setDestinationUDPIP2(const IpAddr ip, Positions pos = {},
const int rx_index = 0);
Result<MacAddr> getDestinationUDPMAC(Positions pos = {}) const; Result<MacAddr> getDestinationUDPMAC(Positions pos = {},
const int rxIndex = 0) const;
/** Mac address of the receiver (destination) udp interface. Not mandatory /** Mac address of the receiver (destination) udp interface. Not mandatory
* to set as setDestinationUDPIP (udp_dstip) retrieves it from slsReceiver * to set as setDestinationUDPIP (udp_dstip) retrieves it from slsReceiver
* process but must be set if you use a custom receiver (not slsReceiver). * process but must be set if you use a custom receiver (not slsReceiver).
*/ */
void setDestinationUDPMAC(const MacAddr mac, Positions pos = {}); void setDestinationUDPMAC(const MacAddr mac, Positions pos = {},
const int rx_index = 0);
/** [Jungfrau] bottom half \n [Gotthard2] veto debugging */ /** [Jungfrau] bottom half \n [Gotthard2] veto debugging */
Result<MacAddr> getDestinationUDPMAC2(Positions pos = {}) const; Result<MacAddr> getDestinationUDPMAC2(Positions pos = {},
const int rx_index = 0) const;
/* [Jungfrau][Gotthard2] Mac address of the receiver (destination) udp /* [Jungfrau][Gotthard2] Mac address of the receiver (destination) udp
interface 2. \n Not mandatory to set as udp_dstip2 retrieves it from interface 2. \n Not mandatory to set as udp_dstip2 retrieves it from
slsReceiver process but must be set if you use a custom receiver (not slsReceiver process but must be set if you use a custom receiver (not
slsReceiver). \n [Jungfrau] bottom half \n [Gotthard2] veto debugging \n slsReceiver). \n [Jungfrau] bottom half \n [Gotthard2] veto debugging \n
*/ */
void setDestinationUDPMAC2(const MacAddr mac, Positions pos = {}); void setDestinationUDPMAC2(const MacAddr mac, Positions pos = {},
const int rx_index = 0);
Result<int> getDestinationUDPPort(Positions pos = {}) const; Result<int> getDestinationUDPPort(Positions pos = {},
const int rx_index = 0) const;
/** Default is 50001. \n If module_id is -1, ports for each module is /** Default is 50001. \n If module_id is -1, ports for each module is
* calculated (incremented by 1 if no 2nd interface) */ * calculated (incremented by 1 if no 2nd interface) */
void setDestinationUDPPort(int port, int module_id = -1); void setDestinationUDPPort(int port, int module_id = -1,
const int rxIndex = 0);
/** [Eiger] right port[Jungfrau] bottom half [Gotthard2] veto debugging */ /** [Eiger] right port[Jungfrau] bottom half [Gotthard2] veto debugging */
Result<int> getDestinationUDPPort2(Positions pos = {}) const; Result<int> getDestinationUDPPort2(Positions pos = {},
const int rx_index = 0) const;
/** [Eiger] right port[Jungfrau] bottom half [Gotthard2] veto debugging \n /** [Eiger] right port[Jungfrau] bottom half [Gotthard2] veto debugging \n
* Default is 50002. \n If module_id is -1, ports for each module is * Default is 50002. \n If module_id is -1, ports for each module is
* calculated (incremented by 1 if no 2nd interface)*/ * calculated (incremented by 1 if no 2nd interface)*/
void setDestinationUDPPort2(int port, int module_id = -1); void setDestinationUDPPort2(int port, int module_id = -1,
const int rxIndex = 0);
/** Reconfigures Detector with UDP destination. More for debugging as the /** Reconfigures Detector with UDP destination. More for debugging as the
* configuration is done automatically when the detector has sufficient UDP * configuration is done automatically when the detector has sufficient UDP
@ -757,7 +764,8 @@ class Detector {
* information */ * information */
void validateUDPConfiguration(Positions pos = {}); void validateUDPConfiguration(Positions pos = {});
Result<std::string> printRxConfiguration(Positions pos = {}) const; Result<std::string> printRxConfiguration(Positions pos = {},
const int rx_index = 0) const;
/** [Eiger][CTB][Moench][Mythen3] */ /** [Eiger][CTB][Moench][Mythen3] */
Result<bool> getTenGiga(Positions pos = {}) const; Result<bool> getTenGiga(Positions pos = {}) const;
@ -816,7 +824,8 @@ class Detector {
/** true when slsReceiver is used */ /** true when slsReceiver is used */
Result<bool> getUseReceiverFlag(Positions pos = {}) const; Result<bool> getUseReceiverFlag(Positions pos = {}) const;
Result<std::string> getRxHostname(Positions pos = {}) const; Result<std::string> getRxHostname(Positions pos = {},
const int rx_index = 0) const;
/** /**
* Sets receiver hostname or IP address for each module. \n Used for TCP * Sets receiver hostname or IP address for each module. \n Used for TCP
@ -824,20 +833,24 @@ class Detector {
* Also updates receiver with detector parameters. \n Also resets any prior * Also updates receiver with detector parameters. \n Also resets any prior
* receiver property (not on detector). \n receiver is receiver hostname or * receiver property (not on detector). \n receiver is receiver hostname or
* IP address, can include tcp port eg. hostname:port * IP address, can include tcp port eg. hostname:port
*
* rxIndex of -1 is rewritten as 0 (for backwards compatibility)
*/ */
void setRxHostname(const std::string &receiver, Positions pos = {}); void setRxHostname(const std::string &receiver, Positions pos = {}, const int rxIndex = 0);
/** multiple rx hostnames. Single element will set it for all */ /** - single element, assumes rxIndex is 0 (for backwards compatibility).
void setRxHostname(const std::vector<std::string> &name); * - muliple element with pos empty or -1, sets each element for each module (1:1 for backwards compatibility, rxIndex = 0)
* multiple element for specific position, each element for each RR rxr */
void setRxHostname(const std::vector<std::string> &name, Positions pos);
Result<int> getRxPort(Positions pos = {}) const; Result<int> getRxPort(Positions pos = {}, const int rx_index = 0) const;
/** TCP port for client-receiver communication. \n /** TCP port for client-receiver communication. \n
* Default is 1954. \n Must be different if multiple receivers on same pc. * Default is 1954. \n Must be different if multiple receivers on same pc.
* \n Must be first command to set a receiver parameter to be able to * \n Must be first command to set a receiver parameter to be able to
* communicate. \n Multi command will automatically increment port for * communicate. \n Multi command will automatically increment port for
* individual modules.*/ * individual modules.*/
void setRxPort(int port, int module_id = -1); void setRxPort(int port, int module_id = -1, const int rx_index = 0);
Result<int> getRxFifoDepth(Positions pos = {}) const; Result<int> getRxFifoDepth(Positions pos = {}) const;
@ -1015,13 +1028,15 @@ class Detector {
*/ */
void setRxZmqPort(int port, int module_id = -1); void setRxZmqPort(int port, int module_id = -1);
Result<IpAddr> getRxZmqIP(Positions pos = {}) const; Result<IpAddr> getRxZmqIP(Positions pos = {},
const int rx_index = 0) const;
/** Zmq Ip Address from which data is to be streamed out of the receiver. \n /** Zmq Ip Address from which data is to be streamed out of the receiver. \n
* Also restarts receiver zmq streaming if enabled. \n Default is from * Also restarts receiver zmq streaming if enabled. \n Default is from
* rx_hostname. \n Modified only when using an intermediate process between * rx_hostname. \n Modified only when using an intermediate process between
* receiver. */ * receiver. */
void setRxZmqIP(const IpAddr ip, Positions pos = {}); void setRxZmqIP(const IpAddr ip, Positions pos = {},
const int rx_index = 0);
Result<int> getClientZmqPort(Positions pos = {}) const; Result<int> getClientZmqPort(Positions pos = {}) const;
@ -1613,14 +1628,6 @@ class Detector {
/** [CTB] Default is enabled. */ /** [CTB] Default is enabled. */
void setLEDEnable(bool enable, Positions pos = {}); void setLEDEnable(bool enable, Positions pos = {});
void setDacNames(const std::vector<std::string> names);
std::vector<std::string> getDacNames() const;
defs::dacIndex getDacIndex(const std::string& name);
std::string getDacName(defs::dacIndex i);
///@} ///@}
/** @name Pattern */ /** @name Pattern */
@ -1755,13 +1762,10 @@ class Detector {
/** [Jungfrau][Gotthard][CTB][Moench][Mythen3][Gotthard2] /** [Jungfrau][Gotthard][CTB][Moench][Mythen3][Gotthard2]
* Advanced user Function! * Advanced user Function!
* Program firmware from command line, after which detector controller is * Program firmware from command line, after which detector controller is
* rebooted. forceDeleteNormalFile is true, if normal file found * rebooted. [Jungfrau][CTB][Moench] fname is a pof file (full path) \n
* in device tree, it must be deleted, a new device drive created and * [Mythen3][Gotthard2] fname is an rbf file (full path)
* programming continued.[Jungfrau][CTB][Moench] fname is a pof file (full
* path) \n [Mythen3][Gotthard2] fname is an rbf file (full path)
*/ */
void programFPGA(const std::string &fname, const bool forceDeleteNormalFile, void programFPGA(const std::string &fname, Positions pos = {});
Positions pos = {});
/** [Jungfrau][CTB][Moench] Advanced user Function! */ /** [Jungfrau][CTB][Moench] Advanced user Function! */
void resetFPGA(Positions pos = {}); void resetFPGA(Positions pos = {});
@ -1927,6 +1931,7 @@ class Detector {
*/ */
std::string getUserDetails() const; std::string getUserDetails() const;
Result<uint64_t> getRxCurrentFrameIndex(Positions pos = {}) const;
///@} ///@}
private: private:

View File

@ -1056,10 +1056,11 @@ std::string CmdProxy::TemperatureValues(int action) {
std::string CmdProxy::Dac(int action) { std::string CmdProxy::Dac(int action) {
std::ostringstream os; std::ostringstream os;
os << cmd << ' '; os << cmd << ' ';
auto type = det->getDetectorType().squash();
// dac indices only for ctb // dac indices only for ctb
if (args.size() > 0 && action != defs::HELP_ACTION) { if (args.size() > 0 && action != defs::HELP_ACTION) {
if (is_int(args[0]) && type != defs::CHIPTESTBOARD) { if (is_int(args[0]) &&
det->getDetectorType().squash() != defs::CHIPTESTBOARD) {
throw sls::RuntimeError( throw sls::RuntimeError(
"Dac indices can only be used for chip test board. Use daclist " "Dac indices can only be used for chip test board. Use daclist "
"to get list of dac names for current detector."); "to get list of dac names for current detector.");
@ -1076,14 +1077,7 @@ std::string CmdProxy::Dac(int action) {
if (args.empty()) if (args.empty())
WrongNumberOfParameters(1); // This prints slightly wrong WrongNumberOfParameters(1); // This prints slightly wrong
defs::dacIndex dacIndex{}; defs::dacIndex dacIndex = StringTo<defs::dacIndex>(args[0]);
//TODO! Remove if
if (type == defs::CHIPTESTBOARD && !is_int(args[0])) {
dacIndex = det->getDacIndex(args[0]);
} else {
dacIndex = StringTo<defs::dacIndex>(args[0]);
}
bool mV = false; bool mV = false;
if (args.size() == 2) { if (args.size() == 2) {
@ -1101,11 +1095,7 @@ std::string CmdProxy::Dac(int action) {
if (args.empty()) if (args.empty())
WrongNumberOfParameters(1); // This prints slightly wrong WrongNumberOfParameters(1); // This prints slightly wrong
defs::dacIndex dacIndex{}; defs::dacIndex dacIndex = StringTo<defs::dacIndex>(args[0]);
if (type == defs::CHIPTESTBOARD && !is_int(args[0]))
dacIndex = det->getDacIndex(args[0]);
else
dacIndex = StringTo<defs::dacIndex>(args[0]);
bool mV = false; bool mV = false;
if (args.size() == 3) { if (args.size() == 3) {
if ((args[2] != "mv") && (args[2] != "mV")) { if ((args[2] != "mv") && (args[2] != "mV")) {
@ -1125,41 +1115,6 @@ std::string CmdProxy::Dac(int action) {
return os.str(); return os.str();
} }
std::string CmdProxy::DacList(const int action) {
std::ostringstream os;
os << cmd << ' ';
if (action == slsDetectorDefs::HELP_ACTION) {
os << "\n\t[dacname1 dacname2 .. dacname18] \n\t\t[ChipTestBoard] Set "
"the list of dac names for this detector.\n\t\t[All] Gets the "
"list "
"of "
"dac names for every dac for this detector."
<< '\n';
} else if (action == slsDetectorDefs::GET_ACTION) {
if (!args.empty()) {
WrongNumberOfParameters(0);
}
auto t = det->getDacNames();
os << sls::ToString(t) << '\n';
} else if (action == slsDetectorDefs::PUT_ACTION) {
if (det->getDetectorType().squash() != defs::CHIPTESTBOARD) {
throw sls::RuntimeError("This detector already has fixed dac "
"names. Cannot change them.");
}
if (det_id != -1) {
throw sls::RuntimeError("Cannot configure dacnames at module level");
}
if (args.size() != 18) {
WrongNumberOfParameters(18);
}
det->setDacNames(args);
os << ToString(args) << '\n';
} else {
throw sls::RuntimeError("Unknown action");
}
return os.str();
}
std::string CmdProxy::DacValues(int action) { std::string CmdProxy::DacValues(int action) {
std::ostringstream os; std::ostringstream os;
os << cmd << ' '; os << cmd << ' ';
@ -1179,15 +1134,13 @@ std::string CmdProxy::DacValues(int action) {
WrongNumberOfParameters(1); WrongNumberOfParameters(1);
} }
auto t = det->getDacList(); auto t = det->getDacList();
auto names = det->getDacNames();
auto name_it = names.begin();
os << '['; os << '[';
auto it = t.cbegin(); auto it = t.cbegin();
os << ToString(*name_it++) << ' '; os << ToString(*it) << ' ';
os << OutString(det->getDAC(*it++, mv, std::vector<int>{det_id})) os << OutString(det->getDAC(*it++, mv, std::vector<int>{det_id}))
<< (!args.empty() ? " mV" : ""); << (!args.empty() ? " mV" : "");
while (it != t.cend()) { while (it != t.cend()) {
os << ", " << ToString(*name_it++) << ' '; os << ", " << ToString(*it) << ' ';
os << OutString(det->getDAC(*it++, mv, std::vector<int>{det_id})) os << OutString(det->getDAC(*it++, mv, std::vector<int>{det_id}))
<< (!args.empty() ? " mV" : ""); << (!args.empty() ? " mV" : "");
} }
@ -1321,6 +1274,40 @@ std::string CmdProxy::DetectorStatus(int action) {
return os.str(); return os.str();
} }
std::string CmdProxy::RxMissingPackets(int action) {
std::ostringstream os;
os << cmd << ' ';
if (action == defs::HELP_ACTION) {
os << "Number of missing packets for each port in receiver. If "
"negative, they are packets in excess. "
<< '\n';
} else if (action == defs::GET_ACTION) {
if (!args.empty()) {
WrongNumberOfParameters(0);
}
auto mp = det->getNumMissingPackets(std::vector<int>{det_id});
/*
auto tmp = det->getNumMissingPackets(std::vector<int>{det_id});
// convert to signed missing packets (to get excess)
Result<std::vector<int64_t>> mp(tmp.size());
for (unsigned int i = 0; i < mp.size(); ++i) {
mp[i] = static_cast<int64_t>(tmp[i]);
}
OR
Result<std::vector<int64_t>> tmp;
for (auto val : tmp) {
mp.push_back(static_cast<int64_t>(val));
}
*/
os << OutString(mp) << '\n';
} else if (action == defs::PUT_ACTION) {
throw sls::RuntimeError("Cannot put");
} else {
throw sls::RuntimeError("Unknown action");
}
return os.str();
}
std::string CmdProxy::Scan(int action) { std::string CmdProxy::Scan(int action) {
std::ostringstream os; std::ostringstream os;
os << cmd << ' '; os << cmd << ' ';
@ -1497,7 +1484,7 @@ std::string CmdProxy::UDPDestinationList(int action) {
} }
if (rx_id < 0 || rx_id >= MAX_UDP_DESTINATION) { if (rx_id < 0 || rx_id >= MAX_UDP_DESTINATION) {
throw sls::RuntimeError( throw sls::RuntimeError(
"Invalid receiver index to set round robin entry."); std::string("Invalid receiver index ") + std::to_string(rx_id) + std::string(" to set round robin entry."));
} }
auto t = getUdpEntry(); auto t = getUdpEntry();
det->setDestinationUDPList(t, det_id); det->setDestinationUDPList(t, det_id);
@ -1517,7 +1504,7 @@ std::string CmdProxy::UDPDestinationIP(int action) {
"rx_hostname." "rx_hostname."
<< '\n'; << '\n';
} else if (action == defs::GET_ACTION) { } else if (action == defs::GET_ACTION) {
auto t = det->getDestinationUDPIP(std::vector<int>{det_id}); auto t = det->getDestinationUDPIP(std::vector<int>{det_id}, rx_id);
if (!args.empty()) { if (!args.empty()) {
WrongNumberOfParameters(0); WrongNumberOfParameters(0);
} }
@ -1530,11 +1517,11 @@ std::string CmdProxy::UDPDestinationIP(int action) {
auto val = getIpFromAuto(); auto val = getIpFromAuto();
LOG(logINFO) << "Setting udp_dstip of detector " << det_id << " to " LOG(logINFO) << "Setting udp_dstip of detector " << det_id << " to "
<< val; << val;
det->setDestinationUDPIP(val, std::vector<int>{det_id}); det->setDestinationUDPIP(val, std::vector<int>{det_id}, rx_id);
os << val << '\n'; os << val << '\n';
} else { } else {
auto val = IpAddr(args[0]); auto val = IpAddr(args[0]);
det->setDestinationUDPIP(val, std::vector<int>{det_id}); det->setDestinationUDPIP(val, std::vector<int>{det_id}, rx_id);
os << args.front() << '\n'; os << args.front() << '\n';
} }
} else { } else {
@ -1553,7 +1540,7 @@ std::string CmdProxy::UDPDestinationIP2(int action) {
"\n\t[Gotthard2] veto debugging. " "\n\t[Gotthard2] veto debugging. "
<< '\n'; << '\n';
} else if (action == defs::GET_ACTION) { } else if (action == defs::GET_ACTION) {
auto t = det->getDestinationUDPIP2(std::vector<int>{det_id}); auto t = det->getDestinationUDPIP2(std::vector<int>{det_id}, rx_id);
if (!args.empty()) { if (!args.empty()) {
WrongNumberOfParameters(0); WrongNumberOfParameters(0);
} }
@ -1566,11 +1553,11 @@ std::string CmdProxy::UDPDestinationIP2(int action) {
auto val = getIpFromAuto(); auto val = getIpFromAuto();
LOG(logINFO) << "Setting udp_dstip2 of detector " << det_id LOG(logINFO) << "Setting udp_dstip2 of detector " << det_id
<< " to " << val; << " to " << val;
det->setDestinationUDPIP2(val, std::vector<int>{det_id}); det->setDestinationUDPIP2(val, std::vector<int>{det_id}, rx_id);
os << val << '\n'; os << val << '\n';
} else { } else {
auto val = IpAddr(args[0]); auto val = IpAddr(args[0]);
det->setDestinationUDPIP2(val, std::vector<int>{det_id}); det->setDestinationUDPIP2(val, std::vector<int>{det_id}, rx_id);
os << args.front() << '\n'; os << args.front() << '\n';
} }
} else { } else {
@ -1606,33 +1593,54 @@ std::string CmdProxy::ReceiverHostname(int action) {
} }
// multiple arguments // multiple arguments
if (args.size() > 1) { if (args.size() > 1) {
// multiple in mulitple if (rx_id != -1) {
if (args[0].find('+') != std::string::npos) {
throw sls::RuntimeError( throw sls::RuntimeError(
"Cannot add multiple receivers at module level"); "Cannot add multiple receivers at RR level");
} }
// multiple arguments (multiple rxr each)// backwards compatibility
if (args[0].find('+') != std::string::npos) {
if (det_id != -1) { if (det_id != -1) {
throw sls::RuntimeError( throw sls::RuntimeError(
"Cannot add multiple receivers at module level"); "Cannot add multiple receivers for multiple modules at module level");
} }
det->setRxHostname(args); for (int i = 0; i < (int)args.size(); ++i) {
auto t = sls::split(args[i], '+');
det->setRxHostname(t, {i});
os << ToString(t) << '\n';
}
}
// multiple arguments (single rxr each) (for both: each module and RR)
else {
det->setRxHostname(args, {det_id});
os << ToString(args) << '\n'; os << ToString(args) << '\n';
} }
}
// single argument // single argument
else { else {
// multiple receivers concatenated with + // multiple receivers concatenated with +
if (args[0].find('+') != std::string::npos) { if (args[0].find('+') != std::string::npos) {
if (det_id != -1) {
throw sls::RuntimeError(
"Cannot add multiple receivers at module level");
}
auto t = sls::split(args[0], '+'); auto t = sls::split(args[0], '+');
det->setRxHostname(t); if (t.size() <= 0) {
throw sls::RuntimeError("Invalid argument for rx_hostname");
}
// single receiver
if (t.size() == 1) {
det->setRxHostname(t[0], std::vector<int>{det_id});
os << ToString(t[0]) << '\n';
}
// multiple receivers
else {
if (rx_id != -1) {
throw sls::RuntimeError(
"Cannot add multiple receivers at RR level");
}
det->setRxHostname(t, {det_id});
os << ToString(t) << '\n'; os << ToString(t) << '\n';
} }
}
// single receiver // single receiver
else { else {
det->setRxHostname(args[0], std::vector<int>{det_id}); det->setRxHostname(args[0], std::vector<int>{det_id}, rx_id);
os << ToString(args) << '\n'; os << ToString(args) << '\n';
} }
} }
@ -2879,31 +2887,19 @@ std::string CmdProxy::ProgramFpga(int action) {
std::ostringstream os; std::ostringstream os;
os << cmd << ' '; os << cmd << ' ';
if (action == defs::HELP_ACTION) { if (action == defs::HELP_ACTION) {
os << "[fname.pof | fname.rbf (full " os << "[fname.pof | fname.rbf (full path)]\n\t[Jungfrau][Ctb][Moench] "
"path)][(opitonal)--force-delete-normal-file]\n\t[Jungfrau][Ctb][" "Programs FPGA from pof file (full path). Then, detector "
"Moench] Programs FPGA from pof file (full path). Then, detector " "controller is rebooted \n\t[Mythen3][Gotthard2] Programs FPGA "
"controller is rebooted. \n\t\tUse --force-delete-normal-file " "from rbf file (full path). Then, detector controller is "
"argument, if normal file found in device tree, it must be " "rebooted."
"deleted, a new device drive created and programming "
"continued.\n\t[Mythen3][Gotthard2] Programs FPGA from rbf file "
"(full path). Then, detector controller is rebooted."
<< '\n'; << '\n';
} else if (action == defs::GET_ACTION) { } else if (action == defs::GET_ACTION) {
throw sls::RuntimeError("Cannot get"); throw sls::RuntimeError("Cannot get");
} else if (action == defs::PUT_ACTION) { } else if (action == defs::PUT_ACTION) {
bool forceDeteleNormalFile = false; if (args.size() != 1) {
if (args.size() == 2) {
if (args[1] != "--force-delete-normal-file") {
throw sls::RuntimeError(
"Could not scan second argument. Did you "
"mean --force-delete-normal-file?");
}
forceDeteleNormalFile = true;
} else if (args.size() != 1) {
WrongNumberOfParameters(1); WrongNumberOfParameters(1);
} }
det->programFPGA(args[0], forceDeteleNormalFile, det->programFPGA(args[0], std::vector<int>{det_id});
std::vector<int>{det_id});
os << "successful\n"; os << "successful\n";
} else { } else {
throw sls::RuntimeError("Unknown action"); throw sls::RuntimeError("Unknown action");

View File

@ -185,8 +185,34 @@
return os.str(); \ return os.str(); \
} }
#define INTEGER_COMMAND_VEC_ID_RX(CMDNAME, GETFCN, SETFCN, CONV, HLPSTR) \
std::string CMDNAME(const int action) { \
std::ostringstream os; \
os << cmd << ' '; \
if (action == slsDetectorDefs::HELP_ACTION) \
os << HLPSTR << '\n'; \
else if (action == slsDetectorDefs::GET_ACTION) { \
if (!args.empty()) { \
WrongNumberOfParameters(0); \
} \
auto t = det->GETFCN(std::vector<int>{det_id}, rx_id); \
os << OutString(t) << '\n'; \
} else if (action == slsDetectorDefs::PUT_ACTION) { \
if (args.size() != 1) { \
WrongNumberOfParameters(1); \
} \
auto val = CONV(args[0]); \
det->SETFCN(val, std::vector<int>{det_id}, rx_id); \
os << args.front() << '\n'; \
} else { \
throw sls::RuntimeError("Unknown action"); \
} \
return os.str(); \
}
/** int or enum */ /** int or enum */
#define INTEGER_COMMAND_VEC_ID_GET(CMDNAME, GETFCN, SETFCN, CONV, HLPSTR) \ #define INTEGER_COMMAND_VEC_ID_PUT_SINGLE_ID(CMDNAME, GETFCN, SETFCN, CONV, \
HLPSTR) \
std::string CMDNAME(const int action) { \ std::string CMDNAME(const int action) { \
std::ostringstream os; \ std::ostringstream os; \
os << cmd << ' '; \ os << cmd << ' '; \
@ -211,6 +237,32 @@
return os.str(); \ return os.str(); \
} }
#define INTEGER_COMMAND_VEC_ID_P_RX_SINGLE_ID(CMDNAME, GETFCN, SETFCN, CONV, \
HLPSTR) \
std::string CMDNAME(const int action) { \
std::ostringstream os; \
os << cmd << ' '; \
if (action == slsDetectorDefs::HELP_ACTION) \
os << HLPSTR << '\n'; \
else if (action == slsDetectorDefs::GET_ACTION) { \
if (!args.empty()) { \
WrongNumberOfParameters(0); \
} \
auto t = det->GETFCN(std::vector<int>{det_id}, rx_id); \
os << OutString(t) << '\n'; \
} else if (action == slsDetectorDefs::PUT_ACTION) { \
if (args.size() != 1) { \
WrongNumberOfParameters(1); \
} \
auto val = CONV(args[0]); \
det->SETFCN(val, det_id, rx_id); \
os << args.front() << '\n'; \
} else { \
throw sls::RuntimeError("Unknown action"); \
} \
return os.str(); \
}
/** int or enum */ /** int or enum */
#define INTEGER_COMMAND_SINGLE_ID(CMDNAME, GETFCN, SETFCN, CONV, HLPSTR) \ #define INTEGER_COMMAND_SINGLE_ID(CMDNAME, GETFCN, SETFCN, CONV, HLPSTR) \
std::string CMDNAME(const int action) { \ std::string CMDNAME(const int action) { \
@ -461,6 +513,26 @@
return os.str(); \ return os.str(); \
} }
#define GET_COMMAND_RX(CMDNAME, GETFCN, HLPSTR) \
std::string CMDNAME(const int action) { \
std::ostringstream os; \
os << cmd << ' '; \
if (action == slsDetectorDefs::HELP_ACTION) \
os << HLPSTR << '\n'; \
else if (action == slsDetectorDefs::GET_ACTION) { \
if (!args.empty()) { \
WrongNumberOfParameters(0); \
} \
auto t = det->GETFCN(std::vector<int>{det_id}); \
os << OutString(t) << '\n'; \
} else if (action == slsDetectorDefs::PUT_ACTION) { \
throw sls::RuntimeError("Cannot put"); \
} else { \
throw sls::RuntimeError("Unknown action"); \
} \
return os.str(); \
}
/** get only no id (vector, not result) */ /** get only no id (vector, not result) */
#define GET_COMMAND_NOID(CMDNAME, GETFCN, HLPSTR) \ #define GET_COMMAND_NOID(CMDNAME, GETFCN, HLPSTR) \
std::string CMDNAME(const int action) { \ std::string CMDNAME(const int action) { \
@ -837,7 +909,7 @@ class CmdProxy {
/* dacs */ /* dacs */
{"dac", &CmdProxy::Dac}, {"dac", &CmdProxy::Dac},
{"daclist", &CmdProxy::DacList}, {"daclist", &CmdProxy::daclist},
{"dacvalues", &CmdProxy::DacValues}, {"dacvalues", &CmdProxy::DacValues},
{"resetdacs", &CmdProxy::ResetDacs}, {"resetdacs", &CmdProxy::ResetDacs},
{"defaultdac", &CmdProxy::DefaultDac}, {"defaultdac", &CmdProxy::DefaultDac},
@ -860,8 +932,7 @@ class CmdProxy {
{"rx_status", &CmdProxy::ReceiverStatus}, {"rx_status", &CmdProxy::ReceiverStatus},
{"status", &CmdProxy::DetectorStatus}, {"status", &CmdProxy::DetectorStatus},
{"rx_framescaught", &CmdProxy::rx_framescaught}, {"rx_framescaught", &CmdProxy::rx_framescaught},
{"rx_missingpackets", &CmdProxy::rx_missingpackets}, {"rx_missingpackets", &CmdProxy::RxMissingPackets},
{"rx_frameindex", &CmdProxy::rx_frameindex},
{"nextframenumber", &CmdProxy::nextframenumber}, {"nextframenumber", &CmdProxy::nextframenumber},
{"trigger", &CmdProxy::Trigger}, {"trigger", &CmdProxy::Trigger},
{"scan", &CmdProxy::Scan}, {"scan", &CmdProxy::Scan},
@ -1087,7 +1158,8 @@ class CmdProxy {
{"framecounter", &CmdProxy::framecounter}, {"framecounter", &CmdProxy::framecounter},
{"runtime", &CmdProxy::runtime}, {"runtime", &CmdProxy::runtime},
{"frametime", &CmdProxy::frametime}, {"frametime", &CmdProxy::frametime},
{"user", &CmdProxy::UserDetails} {"user", &CmdProxy::UserDetails},
{"rx_frameindex", &CmdProxy::rx_frameindex}
}; };
@ -1124,7 +1196,6 @@ class CmdProxy {
std::string TemperatureValues(int action); std::string TemperatureValues(int action);
/* dacs */ /* dacs */
std::string Dac(int action); std::string Dac(int action);
std::string DacList(int action);
std::string DacValues(int action); std::string DacValues(int action);
std::string ResetDacs(int action); std::string ResetDacs(int action);
std::string DefaultDac(int action); std::string DefaultDac(int action);
@ -1283,7 +1354,7 @@ class CmdProxy {
"interfaces must be set to 2. slsReceiver and slsDetectorGui " "interfaces must be set to 2. slsReceiver and slsDetectorGui "
"does not handle."); "does not handle.");
INTEGER_COMMAND_VEC_ID_GET( INTEGER_COMMAND_VEC_ID_PUT_SINGLE_ID(
master, getMaster, setMaster, StringTo<int>, master, getMaster, setMaster, StringTo<int>,
"[0, 1]\n\t[Eiger] Sets half module to master and " "[0, 1]\n\t[Eiger] Sets half module to master and "
"others to slaves.\n\t[Gotthard][Gotthard2][Mythen3][Eiger] " "others to slaves.\n\t[Gotthard][Gotthard2][Mythen3][Eiger] "
@ -1466,6 +1537,10 @@ class CmdProxy {
/* dacs */ /* dacs */
GET_COMMAND_NOID(
daclist, getDacList,
"\n\tGets the list of commands for every dac for this detector.");
/* on chip dacs */ /* on chip dacs */
INTEGER_USER_IND_COMMAND( INTEGER_USER_IND_COMMAND(
vchip_comp_fe, getOnChipDAC, setOnChipDAC, StringTo<int>, vchip_comp_fe, getOnChipDAC, setOnChipDAC, StringTo<int>,
@ -1537,15 +1612,11 @@ class CmdProxy {
"to IDLE or STOPPED. Goes to stop server."); "to IDLE or STOPPED. Goes to stop server.");
GET_COMMAND(rx_framescaught, getFramesCaught, GET_COMMAND(rx_framescaught, getFramesCaught,
"\n\tNumber of frames caught by each port in receiver."); "\n\tNumber of frames caught by receiver.");
GET_COMMAND(rx_missingpackets, getNumMissingPackets, GET_COMMAND(rx_missingpackets, getNumMissingPackets,
"\n\tNumber of missing packets for each port in receiver. If " "\n\tNumber of missing packets for each port in receiver. "
"negative, they are packets in excess. "); "Negative number denotes extra packets.");
GET_COMMAND(rx_frameindex, getRxCurrentFrameIndex,
"\n\tCurrent frame index received for each port in receiver "
"during acquisition.");
INTEGER_COMMAND_VEC_ID( INTEGER_COMMAND_VEC_ID(
nextframenumber, getNextFrameNumber, setNextFrameNumber, nextframenumber, getNextFrameNumber, setNextFrameNumber,
@ -1618,14 +1689,14 @@ class CmdProxy {
"[x:x:x:x:x:x]\n\t[Jungfrau] Mac address of the top " "[x:x:x:x:x:x]\n\t[Jungfrau] Mac address of the top "
"half or inner (source) udp interface. "); "half or inner (source) udp interface. ");
INTEGER_COMMAND_VEC_ID( INTEGER_COMMAND_VEC_ID_RX(
udp_dstmac, getDestinationUDPMAC, setDestinationUDPMAC, MacAddr, udp_dstmac, getDestinationUDPMAC, setDestinationUDPMAC, MacAddr,
"[x:x:x:x:x:x]\n\tMac address of the receiver (destination) udp " "[x:x:x:x:x:x]\n\tMac address of the receiver (destination) udp "
"interface. Not mandatory to set as udp_dstip retrieves it from " "interface. Not mandatory to set as udp_dstip retrieves it from "
"slsReceiver process, but must be set if you use a custom receiver " "slsReceiver process, but must be set if you use a custom receiver "
"(not slsReceiver)."); "(not slsReceiver).");
INTEGER_COMMAND_VEC_ID( INTEGER_COMMAND_VEC_ID_RX(
udp_dstmac2, getDestinationUDPMAC2, setDestinationUDPMAC2, MacAddr, udp_dstmac2, getDestinationUDPMAC2, setDestinationUDPMAC2, MacAddr,
"[x:x:x:x:x:x]\n\t[Jungfrau] Mac address of the receiver (destination) " "[x:x:x:x:x:x]\n\t[Jungfrau] Mac address of the receiver (destination) "
"udp interface 2. Not mandatory to set as udp_dstip2 retrieves it from " "udp interface 2. Not mandatory to set as udp_dstip2 retrieves it from "
@ -1634,14 +1705,14 @@ class CmdProxy {
"[Gotthard2] veto " "[Gotthard2] veto "
"debugging."); "debugging.");
INTEGER_COMMAND_VEC_ID_GET( INTEGER_COMMAND_VEC_ID_P_RX_SINGLE_ID(
udp_dstport, getDestinationUDPPort, setDestinationUDPPort, udp_dstport, getDestinationUDPPort, setDestinationUDPPort,
StringTo<int>, StringTo<int>,
"[n]\n\tPort number of the receiver (destination) udp " "[n]\n\tPort number of the receiver (destination) udp "
"interface. Default is 50001. \n\tIf multi command, ports for each " "interface. Default is 50001. \n\tIf multi command, ports for each "
"module is calculated (incremented by 1 if no 2nd interface)"); "module is calculated (incremented by 1 if no 2nd interface)");
INTEGER_COMMAND_VEC_ID_GET( INTEGER_COMMAND_VEC_ID_P_RX_SINGLE_ID(
udp_dstport2, getDestinationUDPPort2, setDestinationUDPPort2, udp_dstport2, getDestinationUDPPort2, setDestinationUDPPort2,
StringTo<int>, StringTo<int>,
"[n]\n\t[Jungfrau][Eiger][Gotthard2] Port number of the " "[n]\n\t[Jungfrau][Eiger][Gotthard2] Port number of the "
@ -1663,7 +1734,7 @@ class CmdProxy {
"valid. If not configured, it will throw with error message " "valid. If not configured, it will throw with error message "
"requesting missing udp information."); "requesting missing udp information.");
GET_COMMAND(rx_printconfig, printRxConfiguration, GET_COMMAND_RX(rx_printconfig, printRxConfiguration,
"\n\tPrints the receiver configuration."); "\n\tPrints the receiver configuration.");
INTEGER_COMMAND_VEC_ID( INTEGER_COMMAND_VEC_ID(
@ -1700,7 +1771,7 @@ class CmdProxy {
/* Receiver Config */ /* Receiver Config */
INTEGER_COMMAND_VEC_ID_GET( INTEGER_COMMAND_VEC_ID_P_RX_SINGLE_ID(
rx_tcpport, getRxPort, setRxPort, StringTo<int>, rx_tcpport, getRxPort, setRxPort, StringTo<int>,
"[port]\n\tTCP port for client-receiver communication. Default is " "[port]\n\tTCP port for client-receiver communication. Default is "
"1954. Must be different if multiple receivers on same pc. Must be " "1954. Must be different if multiple receivers on same pc. Must be "
@ -1825,7 +1896,7 @@ class CmdProxy {
"default, which streams the first frame in an acquisition, " "default, which streams the first frame in an acquisition, "
"and then depending on the rx zmq frequency/ timer"); "and then depending on the rx zmq frequency/ timer");
INTEGER_COMMAND_VEC_ID_GET( INTEGER_COMMAND_VEC_ID_PUT_SINGLE_ID(
rx_zmqport, getRxZmqPort, setRxZmqPort, StringTo<int>, rx_zmqport, getRxZmqPort, setRxZmqPort, StringTo<int>,
"[port]\n\tZmq port for data to be streamed out of the receiver. Also " "[port]\n\tZmq port for data to be streamed out of the receiver. Also "
"restarts receiver zmq streaming if enabled. Default is 30001. " "restarts receiver zmq streaming if enabled. Default is 30001. "
@ -1833,7 +1904,7 @@ class CmdProxy {
"client(gui). Must be different for every detector (and udp port). " "client(gui). Must be different for every detector (and udp port). "
"Multi command will automatically increment for individual modules."); "Multi command will automatically increment for individual modules.");
INTEGER_COMMAND_VEC_ID_GET( INTEGER_COMMAND_VEC_ID_PUT_SINGLE_ID(
zmqport, getClientZmqPort, setClientZmqPort, StringTo<int>, zmqport, getClientZmqPort, setClientZmqPort, StringTo<int>,
"[port]\n\tZmq port in client(gui) or intermediate process for data to " "[port]\n\tZmq port in client(gui) or intermediate process for data to "
"be streamed to from receiver. Default connects to receiver zmq " "be streamed to from receiver. Default connects to receiver zmq "
@ -1843,7 +1914,7 @@ class CmdProxy {
"port). Multi command will automatically increment for individual " "port). Multi command will automatically increment for individual "
"modules."); "modules.");
INTEGER_COMMAND_VEC_ID( INTEGER_COMMAND_VEC_ID_RX(
rx_zmqip, getRxZmqIP, setRxZmqIP, IpAddr, rx_zmqip, getRxZmqIP, setRxZmqIP, IpAddr,
"[x.x.x.x]\n\tZmq Ip Address from which data is to be streamed out of " "[x.x.x.x]\n\tZmq Ip Address from which data is to be streamed out of "
"the receiver. Also restarts receiver zmq streaming if enabled. " "the receiver. Also restarts receiver zmq streaming if enabled. "
@ -2263,6 +2334,10 @@ class CmdProxy {
"ns|us|ms|s]\n\t[Jungfrau][Mythen3][Gotthard2][Moench][" "ns|us|ms|s]\n\t[Jungfrau][Mythen3][Gotthard2][Moench]["
"CTB] Timestamp at a frame start." "CTB] Timestamp at a frame start."
"\n\t[Gotthard2] not in burst and auto mode."); "\n\t[Gotthard2] not in burst and auto mode.");
GET_COMMAND(
rx_frameindex, getRxCurrentFrameIndex,
"\n\tCurrent frame index received in receiver during acquisition.");
}; };
} // namespace sls } // namespace sls

View File

@ -1,72 +0,0 @@
#include "CtbConfig.h"
#include "SharedMemory.h"
#include "sls/ToString.h"
#include "sls/string_utils.h"
#include <algorithm>
#include <fstream>
#include <sstream>
namespace sls {
CtbConfig::CtbConfig(){
for (size_t i=0; i!=num_dacs; ++i){
setDacName(i, "dac"+ToString(i));
}
}
void CtbConfig::check_index(size_t i) const {
if (!(i < num_dacs)) {
std::ostringstream oss;
oss << "DAC index is too large needs to be below " << num_dacs;
throw RuntimeError(oss.str());
}
}
void CtbConfig::check_size(const std::string &name) const {
if (name.empty())
throw RuntimeError("Name needs to be at least one character");
// dacname_length -1 to account for \0 termination
if (!(name.size() < (name_length - 1))) {
std::ostringstream oss;
oss << "Length of name needs to be less than " << name_length - 1
<< " chars";
throw RuntimeError(oss.str());
}
}
void CtbConfig::setDacName(size_t index, const std::string &name) {
check_index(index);
check_size(name);
char *dst = &dacnames[index * name_length];
memset(dst, '\0', name_length);
memcpy(dst, &name[0], name.size());
}
void CtbConfig::setDacNames(const std::vector<std::string>& names){
for (size_t i = 0; i!=num_dacs; ++i){
setDacName(i, names[i]);
}
}
std::string CtbConfig::getDacName(size_t index) const {
return dacnames + index * name_length;
}
std::vector<std::string> CtbConfig::getDacNames() const {
std::vector<std::string> names;
for (size_t i = 0; i != num_dacs; ++i)
names.push_back(getDacName(i));
return names;
}
const char* CtbConfig::shm_tag(){
return shm_tag_;
}
} // namespace sls

View File

@ -1,31 +0,0 @@
#pragma once
#include <string>
#include <vector>
namespace sls {
class CtbConfig {
static constexpr size_t name_length = 20;
static constexpr size_t num_dacs = 18;
static constexpr const char* shm_tag_ = "ctbdacs";
char dacnames[name_length * num_dacs]{};
void check_index(size_t i) const;
void check_size(const std::string &name) const;
public:
CtbConfig();
CtbConfig(const CtbConfig&) = default;
CtbConfig(CtbConfig&&) = default;
CtbConfig& operator=(const CtbConfig&) = default;
~CtbConfig() = default;
void setDacNames(const std::vector<std::string> &names);
void setDacName(size_t index, const std::string &name);
std::string getDacName(size_t index) const;
std::vector<std::string> getDacNames() const;
static const char* shm_tag();
};
} // namespace sls

View File

@ -7,7 +7,6 @@
#include "CmdProxy.h" #include "CmdProxy.h"
#include "DetectorImpl.h" #include "DetectorImpl.h"
#include "Module.h" #include "Module.h"
#include "CtbConfig.h"
#include "sls/Pattern.h" #include "sls/Pattern.h"
#include "sls/container_utils.h" #include "sls/container_utils.h"
#include "sls/file_utils.h" #include "sls/file_utils.h"
@ -22,12 +21,11 @@
namespace sls { namespace sls {
void freeSharedMemory(int detectorIndex, int moduleIndex) { void freeSharedMemory(int detectorIndex, int moduleIndex) {
// single module // single module
if (moduleIndex >= 0) { if (moduleIndex >= 0) {
SharedMemory<sharedModule> moduleShm(detectorIndex, moduleIndex); SharedMemory<sharedModule> moduleShm(detectorIndex, moduleIndex);
if (moduleShm.exists()) { if (moduleShm.IsExisting()) {
moduleShm.removeSharedMemory(); moduleShm.RemoveSharedMemory();
} }
return; return;
} }
@ -36,21 +34,16 @@ void freeSharedMemory(int detectorIndex, int moduleIndex) {
SharedMemory<sharedDetector> detectorShm(detectorIndex, -1); SharedMemory<sharedDetector> detectorShm(detectorIndex, -1);
int numDetectors = 0; int numDetectors = 0;
if (detectorShm.exists()) { if (detectorShm.IsExisting()) {
detectorShm.openSharedMemory(); detectorShm.OpenSharedMemory();
numDetectors = detectorShm()->numberOfModules; numDetectors = detectorShm()->numberOfModules;
detectorShm.removeSharedMemory(); detectorShm.RemoveSharedMemory();
} }
for (int i = 0; i < numDetectors; ++i) { for (int i = 0; i < numDetectors; ++i) {
SharedMemory<sharedModule> moduleShm(detectorIndex, i); SharedMemory<sharedModule> moduleShm(detectorIndex, i);
moduleShm.removeSharedMemory(); moduleShm.RemoveSharedMemory();
} }
// Ctb configuration
SharedMemory<CtbConfig> ctbShm(detectorIndex, -1, CtbConfig::shm_tag());
if (ctbShm.exists())
ctbShm.removeSharedMemory();
} }
using defs = slsDetectorDefs; using defs = slsDetectorDefs;
@ -836,7 +829,7 @@ Result<defs::runStatus> Detector::getReceiverStatus(Positions pos) const {
return pimpl->Parallel(&Module::getReceiverStatus, pos); return pimpl->Parallel(&Module::getReceiverStatus, pos);
} }
Result<std::vector<int64_t>> Detector::getFramesCaught(Positions pos) const { Result<int64_t> Detector::getFramesCaught(Positions pos) const {
return pimpl->Parallel(&Module::getFramesCaughtByReceiver, pos); return pimpl->Parallel(&Module::getFramesCaughtByReceiver, pos);
} }
@ -845,11 +838,6 @@ Detector::getNumMissingPackets(Positions pos) const {
return pimpl->Parallel(&Module::getNumMissingPackets, pos); return pimpl->Parallel(&Module::getNumMissingPackets, pos);
} }
Result<std::vector<int64_t>>
Detector::getRxCurrentFrameIndex(Positions pos) const {
return pimpl->Parallel(&Module::getReceiverCurrentFrameIndex, pos);
}
Result<uint64_t> Detector::getNextFrameNumber(Positions pos) const { Result<uint64_t> Detector::getNextFrameNumber(Positions pos) const {
return pimpl->Parallel(&Module::getNextFrameNumber, pos); return pimpl->Parallel(&Module::getNextFrameNumber, pos);
} }
@ -883,7 +871,7 @@ Result<std::string> Detector::getScanErrorMessage(Positions pos) const {
Result<int> Detector::getNumberofUDPInterfaces(Positions pos) const { Result<int> Detector::getNumberofUDPInterfaces(Positions pos) const {
// also called by vetostream (for gotthard2) // also called by vetostream (for gotthard2)
return pimpl->Parallel(&Module::getNumberofUDPInterfacesFromShm, pos); return pimpl->getNumberofUDPInterfaces(pos);
} }
void Detector::setNumberofUDPInterfaces(int n, Positions pos) { void Detector::setNumberofUDPInterfaces(int n, Positions pos) {
@ -989,67 +977,81 @@ void Detector::setFirstUDPDestination(const int value, Positions pos) {
pimpl->Parallel(&Module::setFirstUDPDestination, pos, value); pimpl->Parallel(&Module::setFirstUDPDestination, pos, value);
} }
Result<IpAddr> Detector::getDestinationUDPIP(Positions pos) const { Result<IpAddr> Detector::getDestinationUDPIP(Positions pos,
return pimpl->Parallel(&Module::getDestinationUDPIP, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getDestinationUDPIP, pos, rx_index);
} }
void Detector::setDestinationUDPIP(const IpAddr ip, Positions pos) { void Detector::setDestinationUDPIP(const IpAddr ip, Positions pos,
pimpl->Parallel(&Module::setDestinationUDPIP, pos, ip); const int rx_index) {
pimpl->Parallel(&Module::setDestinationUDPIP, pos, ip, rx_index);
} }
Result<IpAddr> Detector::getDestinationUDPIP2(Positions pos) const { Result<IpAddr> Detector::getDestinationUDPIP2(Positions pos,
return pimpl->Parallel(&Module::getDestinationUDPIP2, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getDestinationUDPIP2, pos, rx_index);
} }
void Detector::setDestinationUDPIP2(const IpAddr ip, Positions pos) { void Detector::setDestinationUDPIP2(const IpAddr ip, Positions pos,
pimpl->Parallel(&Module::setDestinationUDPIP2, pos, ip); const int rx_index) {
pimpl->Parallel(&Module::setDestinationUDPIP2, pos, ip, rx_index);
} }
Result<MacAddr> Detector::getDestinationUDPMAC(Positions pos) const { Result<MacAddr> Detector::getDestinationUDPMAC(Positions pos,
return pimpl->Parallel(&Module::getDestinationUDPMAC, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getDestinationUDPMAC, pos, rx_index);
} }
void Detector::setDestinationUDPMAC(const MacAddr mac, Positions pos) { void Detector::setDestinationUDPMAC(const MacAddr mac, Positions pos,
pimpl->Parallel(&Module::setDestinationUDPMAC, pos, mac); const int rx_index) {
pimpl->Parallel(&Module::setDestinationUDPMAC, pos, mac, rx_index);
} }
Result<MacAddr> Detector::getDestinationUDPMAC2(Positions pos) const { Result<MacAddr> Detector::getDestinationUDPMAC2(Positions pos,
return pimpl->Parallel(&Module::getDestinationUDPMAC2, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getDestinationUDPMAC2, pos, rx_index);
} }
void Detector::setDestinationUDPMAC2(const MacAddr mac, Positions pos) { void Detector::setDestinationUDPMAC2(const MacAddr mac, Positions pos,
pimpl->Parallel(&Module::setDestinationUDPMAC2, pos, mac); const int rx_index) {
pimpl->Parallel(&Module::setDestinationUDPMAC2, pos, mac, rx_index);
} }
Result<int> Detector::getDestinationUDPPort(Positions pos) const { Result<int> Detector::getDestinationUDPPort(Positions pos,
return pimpl->Parallel(&Module::getDestinationUDPPort, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getDestinationUDPPort, pos, rx_index);
} }
void Detector::setDestinationUDPPort(int port, int module_id) { void Detector::setDestinationUDPPort(int port, int module_id,
const int rx_index) {
if (module_id == -1) { if (module_id == -1) {
std::vector<int> port_list = getPortNumbers(port); std::vector<int> port_list = getPortNumbers(port);
for (int idet = 0; idet < size(); ++idet) { for (int idet = 0; idet < size(); ++idet) {
pimpl->Parallel(&Module::setDestinationUDPPort, {idet}, pimpl->Parallel(&Module::setDestinationUDPPort, {idet},
port_list[idet]); port_list[idet], rx_index);
} }
} else { } else {
pimpl->Parallel(&Module::setDestinationUDPPort, {module_id}, port); pimpl->Parallel(&Module::setDestinationUDPPort, {module_id}, port,
rx_index);
} }
} }
Result<int> Detector::getDestinationUDPPort2(Positions pos) const { Result<int> Detector::getDestinationUDPPort2(Positions pos,
return pimpl->Parallel(&Module::getDestinationUDPPort2, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getDestinationUDPPort2, pos, rx_index);
} }
void Detector::setDestinationUDPPort2(int port, int module_id) { void Detector::setDestinationUDPPort2(int port, int module_id,
const int rx_index) {
if (module_id == -1) { if (module_id == -1) {
std::vector<int> port_list = getPortNumbers(port); std::vector<int> port_list = getPortNumbers(port);
for (int idet = 0; idet < size(); ++idet) { for (int idet = 0; idet < size(); ++idet) {
pimpl->Parallel(&Module::setDestinationUDPPort2, {idet}, pimpl->Parallel(&Module::setDestinationUDPPort2, {idet},
port_list[idet]); port_list[idet], rx_index);
} }
} else { } else {
pimpl->Parallel(&Module::setDestinationUDPPort2, {module_id}, port); pimpl->Parallel(&Module::setDestinationUDPPort2, {module_id}, port,
rx_index);
} }
} }
@ -1061,8 +1063,9 @@ void Detector::validateUDPConfiguration(Positions pos) {
pimpl->Parallel(&Module::validateUDPConfiguration, pos); pimpl->Parallel(&Module::validateUDPConfiguration, pos);
} }
Result<std::string> Detector::printRxConfiguration(Positions pos) const { Result<std::string> Detector::printRxConfiguration(Positions pos,
return pimpl->Parallel(&Module::printReceiverConfiguration, pos); const int rx_index) const {
return pimpl->Parallel(&Module::printReceiverConfiguration, pos, rx_index);
} }
Result<bool> Detector::getTenGiga(Positions pos) const { Result<bool> Detector::getTenGiga(Positions pos) const {
@ -1111,48 +1114,61 @@ Result<bool> Detector::getUseReceiverFlag(Positions pos) const {
return pimpl->Parallel(&Module::getUseReceiverFlag, pos); return pimpl->Parallel(&Module::getUseReceiverFlag, pos);
} }
Result<std::string> Detector::getRxHostname(Positions pos) const { Result<std::string> Detector::getRxHostname(Positions pos,
return pimpl->Parallel(&Module::getReceiverHostname, pos); const int rx_index) const {
return pimpl->Parallel(&Module::getReceiverHostname, pos, rx_index);
} }
void Detector::setRxHostname(const std::string &receiver, Positions pos) { // rr added using + at module level
pimpl->Parallel(&Module::setReceiverHostname, pos, receiver); void Detector::setRxHostname(const std::string &receiver, Positions pos,
const int rxIndex) {
// for backwards compatibility
if (rxIndex == -1) {
pimpl->Parallel(&Module::setReceiverHostname, pos, receiver, 0);
} else {
pimpl->Parallel(&Module::setReceiverHostname, pos, receiver, rxIndex);
}
updateRxRateCorrections(); updateRxRateCorrections();
} }
void Detector::setRxHostname(const std::vector<std::string> &name) { void Detector::setRxHostname(const std::vector<std::string> &name,
// set all to same rx_hostname Positions pos) {
if (name.size() == 1) { // multi module (backwards compatibility: every element for every module)
pimpl->Parallel(&Module::setReceiverHostname, {}, name[0]); if (name.size() > 1 && ((pos.empty() || pos[0] == -1))) {
} else {
if ((int)name.size() != size()) { if ((int)name.size() != size()) {
throw RuntimeError( throw RuntimeError(
"Receiver hostnames size " + std::to_string(name.size()) + "Receiver hostnames size " + std::to_string(name.size()) +
" does not match detector size " + std::to_string(size())); " does not match detector size " + std::to_string(size()));
} }
// set each rx_hostname
for (int idet = 0; idet < size(); ++idet) { for (int idet = 0; idet < size(); ++idet) {
pimpl->Parallel(&Module::setReceiverHostname, {idet}, name[idet]); pimpl->Parallel(&Module::setReceiverHostname, {idet}, name[idet],
0);
} }
} }
// setting rr for specific module (backwards compaibility: single element is
// only for 0th RR)
else {
pimpl->Parallel(&Module::setAllReceiverHostnames, {pos}, name);
}
updateRxRateCorrections(); updateRxRateCorrections();
} }
Result<int> Detector::getRxPort(Positions pos) const { Result<int> Detector::getRxPort(Positions pos, const int rx_index) const {
return pimpl->Parallel(&Module::getReceiverPort, pos); return pimpl->Parallel(&Module::getReceiverPort, pos, rx_index);
} }
void Detector::setRxPort(int port, int module_id) { void Detector::setRxPort(int port, int module_id, const int rx_index) {
if (module_id == -1) { if (module_id == -1) {
std::vector<int> port_list(size()); std::vector<int> port_list(size());
for (auto &it : port_list) { for (auto &it : port_list) {
it = port++; it = port++;
} }
for (int idet = 0; idet < size(); ++idet) { for (int idet = 0; idet < size(); ++idet) {
pimpl->Parallel(&Module::setReceiverPort, {idet}, port_list[idet]); pimpl->Parallel(&Module::setReceiverPort, {idet}, port_list[idet],
rx_index);
} }
} else { } else {
pimpl->Parallel(&Module::setReceiverPort, {module_id}, port); pimpl->Parallel(&Module::setReceiverPort, {module_id}, port, rx_index);
} }
} }
@ -1350,13 +1366,13 @@ void Detector::setRxZmqPort(int port, int module_id) {
} }
} }
Result<IpAddr> Detector::getRxZmqIP(Positions pos) const { Result<IpAddr> Detector::getRxZmqIP(Positions pos, const int rx_index) const {
return pimpl->Parallel(&Module::getReceiverStreamingIP, pos); return pimpl->Parallel(&Module::getReceiverStreamingIP, pos, rx_index);
} }
void Detector::setRxZmqIP(const IpAddr ip, Positions pos) { void Detector::setRxZmqIP(const IpAddr ip, Positions pos, const int rx_index) {
bool previouslyReceiverStreaming = getRxZmqDataStream(pos).squash(false); bool previouslyReceiverStreaming = getRxZmqDataStream(pos).squash(false);
pimpl->Parallel(&Module::setReceiverStreamingIP, pos, ip); pimpl->Parallel(&Module::setReceiverStreamingIP, pos, ip, rx_index);
if (previouslyReceiverStreaming) { if (previouslyReceiverStreaming) {
setRxZmqDataStream(false, pos); setRxZmqDataStream(false, pos);
setRxZmqDataStream(true, pos); setRxZmqDataStream(true, pos);
@ -1751,7 +1767,7 @@ Result<defs::streamingInterface> Detector::getVetoStream(Positions pos) const {
// 3gbe // 3gbe
auto r3 = pimpl->Parallel(&Module::getVetoStream, pos); auto r3 = pimpl->Parallel(&Module::getVetoStream, pos);
// 10gbe (debugging interface) opens 2nd udp interface in receiver // 10gbe (debugging interface) opens 2nd udp interface in receiver
auto r10 = getNumberofUDPInterfaces(pos); auto r10 = pimpl->getNumberofUDPInterfaces(pos);
Result<defs::streamingInterface> res(r3.size()); Result<defs::streamingInterface> res(r3.size());
for (unsigned int i = 0; i < res.size(); ++i) { for (unsigned int i = 0; i < res.size(); ++i) {
@ -1773,7 +1789,7 @@ void Detector::setVetoStream(defs::streamingInterface interface,
pimpl->Parallel(&Module::setVetoStream, pos, LOW_LATENCY_LINK); pimpl->Parallel(&Module::setVetoStream, pos, LOW_LATENCY_LINK);
// 10gbe (debugging interface) opens 2nd udp interface in receiver // 10gbe (debugging interface) opens 2nd udp interface in receiver
int old_numinterfaces = getNumberofUDPInterfaces(pos).tsquash( int old_numinterfaces = pimpl->getNumberofUDPInterfaces(pos).tsquash(
"retrieved inconsistent number of udp interfaces"); "retrieved inconsistent number of udp interfaces");
int numinterfaces = int numinterfaces =
(((interface & defs::streamingInterface::ETHERNET_10GB) == (((interface & defs::streamingInterface::ETHERNET_10GB) ==
@ -2074,42 +2090,6 @@ void Detector::setLEDEnable(bool enable, Positions pos) {
pimpl->Parallel(&Module::setLEDEnable, pos, enable); pimpl->Parallel(&Module::setLEDEnable, pos, enable);
} }
void Detector::setDacNames(const std::vector<std::string> names) {
if (getDetectorType().squash() != defs::CHIPTESTBOARD)
throw RuntimeError("Named dacs only for CTB");
pimpl->setCtbDacNames(names);
}
std::vector<std::string> Detector::getDacNames() const {
std::vector<std::string> names;
auto type = getDetectorType().squash();
if (type == defs::CHIPTESTBOARD)
return pimpl->getCtbDacNames();
for (const auto &index : getDacList())
names.push_back(ToString(index));
return names;
}
defs::dacIndex Detector::getDacIndex(const std::string &name) {
auto type = getDetectorType().squash();
if (type == defs::CHIPTESTBOARD) {
auto names = getDacNames();
auto it = std::find(names.begin(), names.end(), name);
if (it == names.end())
throw RuntimeError("Dacname not found");
return static_cast<defs::dacIndex>(it - names.begin());
}
return StringTo<defs::dacIndex>(name);
}
std::string Detector::getDacName(defs::dacIndex i) {
auto type = getDetectorType().squash();
if (type == defs::CHIPTESTBOARD)
return pimpl->getCtbDacName(i);
return ToString(i);
}
// Pattern // Pattern
void Detector::setPattern(const std::string &fname, Positions pos) { void Detector::setPattern(const std::string &fname, Positions pos) {
@ -2230,11 +2210,10 @@ void Detector::setAdditionalJsonParameter(const std::string &key,
// Advanced // Advanced
void Detector::programFPGA(const std::string &fname, void Detector::programFPGA(const std::string &fname, Positions pos) {
const bool forceDeleteNormalFile, Positions pos) {
LOG(logINFO) << "Updating Firmware..."; LOG(logINFO) << "Updating Firmware...";
std::vector<char> buffer = pimpl->readProgrammingFile(fname); std::vector<char> buffer = pimpl->readProgrammingFile(fname);
pimpl->Parallel(&Module::programFPGA, pos, buffer, forceDeleteNormalFile); pimpl->Parallel(&Module::programFPGA, pos, buffer);
rebootController(pos); rebootController(pos);
} }
@ -2279,7 +2258,7 @@ void Detector::updateFirmwareAndServer(const std::string &sname,
LOG(logINFO) << "Updating Firmware and Detector Server (with tftp)..."; LOG(logINFO) << "Updating Firmware and Detector Server (with tftp)...";
LOG(logINFO) << "Updating Detector Server (via tftp)..."; LOG(logINFO) << "Updating Detector Server (via tftp)...";
pimpl->Parallel(&Module::copyDetectorServer, pos, sname, hostname); pimpl->Parallel(&Module::copyDetectorServer, pos, sname, hostname);
programFPGA(fname, false, pos); programFPGA(fname, pos);
} }
void Detector::updateFirmwareAndServer(const std::string &sname, void Detector::updateFirmwareAndServer(const std::string &sname,
@ -2290,7 +2269,7 @@ void Detector::updateFirmwareAndServer(const std::string &sname,
std::vector<char> buffer = readBinaryFile(sname, "Update Detector Server"); std::vector<char> buffer = readBinaryFile(sname, "Update Detector Server");
std::string filename = sls::getFileNameFromFilePath(sname); std::string filename = sls::getFileNameFromFilePath(sname);
pimpl->Parallel(&Module::updateDetectorServer, pos, buffer, filename); pimpl->Parallel(&Module::updateDetectorServer, pos, buffer, filename);
programFPGA(fname, false, pos); programFPGA(fname, pos);
} }
Result<bool> Detector::getUpdateMode(Positions pos) const { Result<bool> Detector::getUpdateMode(Positions pos) const {
@ -2399,8 +2378,12 @@ Result<ns> Detector::getMeasurementTime(Positions pos) const {
std::string Detector::getUserDetails() const { return pimpl->getUserDetails(); } std::string Detector::getUserDetails() const { return pimpl->getUserDetails(); }
Result<uint64_t> Detector::getRxCurrentFrameIndex(Positions pos) const {
return pimpl->Parallel(&Module::getReceiverCurrentFrameIndex, pos);
}
std::vector<int> Detector::getPortNumbers(int start_port) { std::vector<int> Detector::getPortNumbers(int start_port) {
int num_sockets_per_detector = getNumberofUDPInterfaces({}).tsquash( int num_sockets_per_detector = pimpl->getNumberofUDPInterfaces({}).tsquash(
"Number of UDP Interfaces is not consistent among modules"); "Number of UDP Interfaces is not consistent among modules");
std::vector<int> res; std::vector<int> res;
res.reserve(size()); res.reserve(size());

View File

@ -32,8 +32,7 @@
namespace sls { namespace sls {
DetectorImpl::DetectorImpl(int detector_index, bool verify, bool update) DetectorImpl::DetectorImpl(int detector_index, bool verify, bool update)
: detectorIndex(detector_index), shm(detector_index, -1), : detectorIndex(detector_index), shm(detector_index, -1) {
ctb_shm(detector_index, -1, CtbConfig::shm_tag()) {
setupDetector(verify, update); setupDetector(verify, update);
} }
@ -45,9 +44,6 @@ void DetectorImpl::setupDetector(bool verify, bool update) {
if (update) { if (update) {
updateUserdetails(); updateUserdetails();
} }
if (ctb_shm.exists())
ctb_shm.openSharedMemory();
} }
void DetectorImpl::setAcquiringFlag(bool flag) { shm()->acquiringFlag = flag; } void DetectorImpl::setAcquiringFlag(bool flag) { shm()->acquiringFlag = flag; }
@ -58,8 +54,8 @@ void DetectorImpl::freeSharedMemory(int detectorIndex, int detPos) {
// single // single
if (detPos >= 0) { if (detPos >= 0) {
SharedMemory<sharedModule> moduleShm(detectorIndex, detPos); SharedMemory<sharedModule> moduleShm(detectorIndex, detPos);
if (moduleShm.exists()) { if (moduleShm.IsExisting()) {
moduleShm.removeSharedMemory(); moduleShm.RemoveSharedMemory();
} }
return; return;
} }
@ -68,20 +64,16 @@ void DetectorImpl::freeSharedMemory(int detectorIndex, int detPos) {
SharedMemory<sharedDetector> detectorShm(detectorIndex, -1); SharedMemory<sharedDetector> detectorShm(detectorIndex, -1);
int numModules = 0; int numModules = 0;
if (detectorShm.exists()) { if (detectorShm.IsExisting()) {
detectorShm.openSharedMemory(); detectorShm.OpenSharedMemory();
numModules = detectorShm()->numberOfModules; numModules = detectorShm()->numberOfModules;
detectorShm.removeSharedMemory(); detectorShm.RemoveSharedMemory();
} }
for (int i = 0; i < numModules; ++i) { for (int i = 0; i < numModules; ++i) {
SharedMemory<sharedModule> moduleShm(detectorIndex, i); SharedMemory<sharedModule> moduleShm(detectorIndex, i);
moduleShm.removeSharedMemory(); moduleShm.RemoveSharedMemory();
} }
SharedMemory<CtbConfig> ctbShm(detectorIndex, -1, CtbConfig::shm_tag());
if (ctbShm.exists())
ctbShm.removeSharedMemory();
} }
void DetectorImpl::freeSharedMemory() { void DetectorImpl::freeSharedMemory() {
@ -92,11 +84,8 @@ void DetectorImpl::freeSharedMemory() {
modules.clear(); modules.clear();
// clear detector shm // clear detector shm
shm.removeSharedMemory(); shm.RemoveSharedMemory();
client_downstream = false; client_downstream = false;
if (ctb_shm.exists())
ctb_shm.removeSharedMemory();
} }
std::string DetectorImpl::getUserDetails() { std::string DetectorImpl::getUserDetails() {
@ -140,11 +129,11 @@ void DetectorImpl::setInitialChecks(const bool value) {
} }
void DetectorImpl::initSharedMemory(bool verify) { void DetectorImpl::initSharedMemory(bool verify) {
if (!shm.exists()) { if (!shm.IsExisting()) {
shm.createSharedMemory(); shm.CreateSharedMemory();
initializeDetectorStructure(); initializeDetectorStructure();
} else { } else {
shm.openSharedMemory(); shm.OpenSharedMemory();
if (verify && shm()->shmversion != DETECTOR_SHMVERSION) { if (verify && shm()->shmversion != DETECTOR_SHMVERSION) {
LOG(logERROR) << "Detector shared memory (" << detectorIndex LOG(logERROR) << "Detector shared memory (" << detectorIndex
<< ") version mismatch " << ") version mismatch "
@ -155,8 +144,6 @@ void DetectorImpl::initSharedMemory(bool verify) {
throw SharedMemoryError("Shared memory version mismatch!"); throw SharedMemoryError("Shared memory version mismatch!");
} }
} }
// std::cout <<
} }
void DetectorImpl::initializeDetectorStructure() { void DetectorImpl::initializeDetectorStructure() {
@ -259,14 +246,13 @@ void DetectorImpl::setHostname(const std::vector<std::string> &name) {
} }
updateDetectorSize(); updateDetectorSize();
// Here we know the detector type and can add ctb shared memory // update zmq port (especially for eiger)
// if needed, CTB dac names are only on detector level int numInterfaces = modules[0]->getNumberofUDPInterfaces();
if (numInterfaces == 2) {
if (shm()->detType == defs::CHIPTESTBOARD) { for (size_t i = 0; i < modules.size(); ++i) {
if (ctb_shm.exists()) modules[i]->setClientStreamingPort(DEFAULT_ZMQ_CL_PORTNO +
ctb_shm.openSharedMemory(); i * numInterfaces);
else }
ctb_shm.createSharedMemory();
} }
} }
@ -295,13 +281,6 @@ void DetectorImpl::addModule(const std::string &hostname) {
// get type by connecting // get type by connecting
detectorType type = Module::getTypeFromDetector(host, port); detectorType type = Module::getTypeFromDetector(host, port);
// gotthard cannot have more than 2 modules (50um=1, 25um=2
if ((type == GOTTHARD || type == GOTTHARD2) && modules.size() > 2) {
freeSharedMemory();
throw sls::RuntimeError("Gotthard cannot have more than 2 modules");
}
auto pos = modules.size(); auto pos = modules.size();
modules.emplace_back( modules.emplace_back(
sls::make_unique<Module>(type, detectorIndex, pos, false)); sls::make_unique<Module>(type, detectorIndex, pos, false));
@ -309,20 +288,11 @@ void DetectorImpl::addModule(const std::string &hostname) {
modules[pos]->setControlPort(port); modules[pos]->setControlPort(port);
modules[pos]->setStopPort(port + 1); modules[pos]->setStopPort(port + 1);
modules[pos]->setHostname(host, shm()->initialChecks); modules[pos]->setHostname(host, shm()->initialChecks);
// module type updated by now // module type updated by now
shm()->detType = Parallel(&Module::getDetectorType, {}) shm()->detType = Parallel(&Module::getDetectorType, {})
.tsquash("Inconsistent detector types."); .tsquash("Inconsistent detector types.");
// for moench and ctb // for moench and ctb
modules[pos]->updateNumberOfChannels(); modules[pos]->updateNumberOfChannels();
// for eiger, jungfrau, gotthard2
modules[pos]->updateNumberofUDPInterfaces();
// update zmq port in case numudpinterfaces changed
int numInterfaces = modules[pos]->getNumberofUDPInterfacesFromShm();
modules[pos]->setClientStreamingPort(DEFAULT_ZMQ_CL_PORTNO +
pos * numInterfaces);
} }
void DetectorImpl::updateDetectorSize() { void DetectorImpl::updateDetectorSize() {
@ -1172,7 +1142,7 @@ int DetectorImpl::acquire() {
if (acquisition_finished != nullptr) { if (acquisition_finished != nullptr) {
int status = Parallel(&Module::getRunStatus, {}).squash(ERROR); int status = Parallel(&Module::getRunStatus, {}).squash(ERROR);
auto a = Parallel(&Module::getReceiverProgress, {}); auto a = Parallel(&Module::getReceiverProgress, {});
double progress = (*std::max_element(a.begin(), a.end())); double progress = (*std::min_element(a.begin(), a.end()));
acquisition_finished(progress, status, acqFinished_p); acquisition_finished(progress, status, acqFinished_p);
} }
@ -1391,6 +1361,10 @@ std::vector<char> DetectorImpl::readProgrammingFile(const std::string &fname) {
return buffer; return buffer;
} }
sls::Result<int> DetectorImpl::getNumberofUDPInterfaces(Positions pos) const {
return Parallel(&Module::getNumberofUDPInterfaces, pos);
}
sls::Result<int> DetectorImpl::getDefaultDac(defs::dacIndex index, sls::Result<int> DetectorImpl::getDefaultDac(defs::dacIndex index,
defs::detectorSettings sett, defs::detectorSettings sett,
Positions pos) { Positions pos) {
@ -1402,16 +1376,4 @@ void DetectorImpl::setDefaultDac(defs::dacIndex index, int defaultValue,
Parallel(&Module::setDefaultDac, pos, index, defaultValue, sett); Parallel(&Module::setDefaultDac, pos, index, defaultValue, sett);
} }
std::vector<std::string> DetectorImpl::getCtbDacNames() const {
return ctb_shm()->getDacNames();
}
void DetectorImpl::setCtbDacNames(const std::vector<std::string> &names) {
ctb_shm()->setDacNames(names);
}
std::string DetectorImpl::getCtbDacName(defs::dacIndex i) const {
return ctb_shm()->getDacName(static_cast<int>(i));
}
} // namespace sls } // namespace sls

View File

@ -7,8 +7,6 @@
#include "sls/logger.h" #include "sls/logger.h"
#include "sls/sls_detector_defs.h" #include "sls/sls_detector_defs.h"
#include "CtbConfig.h"
class ZmqSocket; class ZmqSocket;
class detectorData; class detectorData;
@ -293,6 +291,7 @@ class DetectorImpl : public virtual slsDetectorDefs {
*/ */
std::vector<char> readProgrammingFile(const std::string &fname); std::vector<char> readProgrammingFile(const std::string &fname);
sls::Result<int> getNumberofUDPInterfaces(Positions pos) const;
void setNumberofUDPInterfaces(int n, Positions pos); void setNumberofUDPInterfaces(int n, Positions pos);
sls::Result<int> getDefaultDac(defs::dacIndex index, sls::Result<int> getDefaultDac(defs::dacIndex index,
defs::detectorSettings sett, defs::detectorSettings sett,
@ -300,11 +299,6 @@ class DetectorImpl : public virtual slsDetectorDefs {
void setDefaultDac(defs::dacIndex index, int defaultValue, void setDefaultDac(defs::dacIndex index, int defaultValue,
defs::detectorSettings sett, Positions pos); defs::detectorSettings sett, Positions pos);
std::vector<std::string> getCtbDacNames() const;
std::string getCtbDacName(defs::dacIndex i) const;
void setCtbDacNames(const std::vector<std::string>& names);
private: private:
/** /**
* Creates/open shared memory, initializes detector structure and members * Creates/open shared memory, initializes detector structure and members
@ -388,7 +382,6 @@ class DetectorImpl : public virtual slsDetectorDefs {
const int detectorIndex{0}; const int detectorIndex{0};
sls::SharedMemory<sharedDetector> shm{0, -1}; sls::SharedMemory<sharedDetector> shm{0, -1};
sls::SharedMemory<CtbConfig> ctb_shm{0, -1, CtbConfig::shm_tag()};
std::vector<std::unique_ptr<sls::Module>> modules; std::vector<std::unique_ptr<sls::Module>> modules;
/** data streaming (down stream) enabled in client (zmq sckets created) */ /** data streaming (down stream) enabled in client (zmq sckets created) */

File diff suppressed because it is too large Load Diff

View File

@ -17,10 +17,15 @@
class ServerInterface; class ServerInterface;
#define MODULE_SHMAPIVERSION 0x190726 #define MODULE_SHMAPIVERSION 0x190726
#define MODULE_SHMVERSION 0x200402 #define MODULE_SHMVERSION 0x210913
namespace sls { namespace sls {
struct sharedReceiver {
char hostname[MAX_STR_LENGTH]{};
int tcpPort{};
};
/** /**
* @short structure allocated in shared memory to store Module settings for * @short structure allocated in shared memory to store Module settings for
* IPC and cache * IPC and cache
@ -45,8 +50,11 @@ struct sharedModule {
slsDetectorDefs::xy nChan; slsDetectorDefs::xy nChan;
slsDetectorDefs::xy nChip; slsDetectorDefs::xy nChip;
int nDacs; int nDacs;
char rxHostname[MAX_STR_LENGTH];
int rxTCPPort; /** receiver details for each module */
int numReceivers;
sharedReceiver receivers[MAX_UDP_DESTINATION];
/** if rxHostname and rxTCPPort can be connected to */ /** if rxHostname and rxTCPPort can be connected to */
bool useReceiverFlag; bool useReceiverFlag;
/** Listening tcp port from gui (only data) */ /** Listening tcp port from gui (only data) */
@ -203,9 +211,8 @@ class Module : public virtual slsDetectorDefs {
runStatus getRunStatus() const; runStatus getRunStatus() const;
runStatus getReceiverStatus() const; runStatus getReceiverStatus() const;
double getReceiverProgress() const; double getReceiverProgress() const;
std::vector<int64_t> getFramesCaughtByReceiver() const; int64_t getFramesCaughtByReceiver() const;
std::vector<int64_t> getNumMissingPackets() const; std::vector<int64_t> getNumMissingPackets() const;
std::vector<int64_t> getReceiverCurrentFrameIndex() const;
uint64_t getNextFrameNumber() const; uint64_t getNextFrameNumber() const;
void setNextFrameNumber(uint64_t value); void setNextFrameNumber(uint64_t value);
void sendSoftwareTrigger(const bool block); void sendSoftwareTrigger(const bool block);
@ -219,7 +226,7 @@ class Module : public virtual slsDetectorDefs {
* * * *
* ************************************************/ * ************************************************/
int getNumberofUDPInterfacesFromShm() const; int getNumberofUDPInterfacesFromShm() const;
void updateNumberofUDPInterfaces(); int getNumberofUDPInterfaces() const;
void setNumberofUDPInterfaces(int n); void setNumberofUDPInterfaces(int n);
int getSelectedUDPInterface() const; int getSelectedUDPInterface() const;
void selectUDPInterface(int n); void selectUDPInterface(int n);
@ -237,21 +244,21 @@ class Module : public virtual slsDetectorDefs {
void clearUDPDestinations(); void clearUDPDestinations();
int getFirstUDPDestination() const; int getFirstUDPDestination() const;
void setFirstUDPDestination(const int value); void setFirstUDPDestination(const int value);
sls::IpAddr getDestinationUDPIP() const; sls::IpAddr getDestinationUDPIP(const int rxIndex) const;
void setDestinationUDPIP(const sls::IpAddr ip); void setDestinationUDPIP(const sls::IpAddr ip, const int rxIndex);
sls::IpAddr getDestinationUDPIP2() const; sls::IpAddr getDestinationUDPIP2(const int rxIndex) const;
void setDestinationUDPIP2(const sls::IpAddr ip); void setDestinationUDPIP2(const sls::IpAddr ip, const int rxIndex);
sls::MacAddr getDestinationUDPMAC() const; sls::MacAddr getDestinationUDPMAC(const int rxIndex) const;
void setDestinationUDPMAC(const sls::MacAddr mac); void setDestinationUDPMAC(const sls::MacAddr mac, const int rxIndex);
sls::MacAddr getDestinationUDPMAC2() const; sls::MacAddr getDestinationUDPMAC2(const int rxIndex) const;
void setDestinationUDPMAC2(const sls::MacAddr mac); void setDestinationUDPMAC2(const sls::MacAddr mac, const int rxIndex);
int getDestinationUDPPort() const; int getDestinationUDPPort(const int rxIndex) const;
void setDestinationUDPPort(int udpport); void setDestinationUDPPort(int udpport, const int rxIndex);
int getDestinationUDPPort2() const; int getDestinationUDPPort2(const int rxIndex) const;
void setDestinationUDPPort2(int udpport); void setDestinationUDPPort2(int udpport, const int rxIndex);
void reconfigureUDPDestination(); void reconfigureUDPDestination();
void validateUDPConfiguration(); void validateUDPConfiguration();
std::string printReceiverConfiguration(); std::string printReceiverConfiguration(const int rxIndex);
bool getTenGiga() const; bool getTenGiga() const;
void setTenGiga(bool value); void setTenGiga(bool value);
bool getTenGigaFlowControl() const; bool getTenGigaFlowControl() const;
@ -269,10 +276,11 @@ class Module : public virtual slsDetectorDefs {
* * * *
* ************************************************/ * ************************************************/
bool getUseReceiverFlag() const; bool getUseReceiverFlag() const;
std::string getReceiverHostname() const; std::string getReceiverHostname(const int rxIndex) const;
void setReceiverHostname(const std::string &receiver); void setAllReceiverHostnames(const std::vector<std::string> &receiver);
int getReceiverPort() const; void setReceiverHostname(const std::string &receiver, const int rxIndex);
int setReceiverPort(int port_number); int getReceiverPort(const int rxIndex) const;
void setReceiverPort(int port_number, const int rxIndex);
int getReceiverFifoDepth() const; int getReceiverFifoDepth() const;
void setReceiverFifoDepth(int n_frames); void setReceiverFifoDepth(int n_frames);
bool getReceiverSilentMode() const; bool getReceiverSilentMode() const;
@ -331,8 +339,8 @@ class Module : public virtual slsDetectorDefs {
void setReceiverStreamingStartingFrame(int fnum); void setReceiverStreamingStartingFrame(int fnum);
int getReceiverStreamingPort() const; int getReceiverStreamingPort() const;
void setReceiverStreamingPort(int port); void setReceiverStreamingPort(int port);
sls::IpAddr getReceiverStreamingIP() const; sls::IpAddr getReceiverStreamingIP(const int rxIndex) const;
void setReceiverStreamingIP(const sls::IpAddr ip); void setReceiverStreamingIP(const sls::IpAddr ip, const int rxIndex);
int getClientStreamingPort() const; int getClientStreamingPort() const;
void setClientStreamingPort(int port); void setClientStreamingPort(int port);
sls::IpAddr getClientStreamingIP() const; sls::IpAddr getClientStreamingIP() const;
@ -545,8 +553,7 @@ class Module : public virtual slsDetectorDefs {
* Advanced * * Advanced *
* * * *
* ************************************************/ * ************************************************/
void programFPGA(std::vector<char> buffer, void programFPGA(std::vector<char> buffer);
const bool forceDeleteNormalFile);
void resetFPGA(); void resetFPGA();
void copyDetectorServer(const std::string &fname, void copyDetectorServer(const std::string &fname,
const std::string &hostname); const std::string &hostname);
@ -583,6 +590,7 @@ class Module : public virtual slsDetectorDefs {
int64_t getNumberOfFramesFromStart() const; int64_t getNumberOfFramesFromStart() const;
int64_t getActualTime() const; int64_t getActualTime() const;
int64_t getMeasurementTime() const; int64_t getMeasurementTime() const;
uint64_t getReceiverCurrentFrameIndex() const;
private: private:
void checkArgs(const void *args, size_t args_size, void *retval, void checkArgs(const void *args, size_t args_size, void *retval,
@ -672,43 +680,52 @@ class Module : public virtual slsDetectorDefs {
Ret sendToDetectorStop(int fnum, const Arg &args) const; Ret sendToDetectorStop(int fnum, const Arg &args) const;
/** Send function parameters to receiver */ /** Send function parameters to receiver */
void sendToReceiver(int fnum, const void *args, size_t args_size, std::vector<int> getEntryList(const int rxIndex) const;
void *retval, size_t retval_size); void sendToReceiver(const int rxIndex, int fnum, const void *args,
size_t args_size, void *retval, size_t retval_size);
void sendToReceiver(int fnum, const void *args, size_t args_size, void sendToReceiver(const int rxIndex, int fnum, const void *args,
void *retval, size_t retval_size) const; size_t args_size, void *retval,
size_t retval_size) const;
template <typename Arg, typename Ret> template <typename Arg, typename Ret>
void sendToReceiver(int fnum, const Arg &args, Ret &retval); void sendToReceiver(const int rxIndex, int fnum, const Arg &args,
Ret &retval);
template <typename Arg, typename Ret> template <typename Arg, typename Ret>
void sendToReceiver(int fnum, const Arg &args, Ret &retval) const; void sendToReceiver(const int rxIndex, int fnum, const Arg &args,
Ret &retval) const;
template <typename Arg> template <typename Arg>
void sendToReceiver(int fnum, const Arg &args, std::nullptr_t); void sendToReceiver(const int rxIndex, int fnum, const Arg &args,
std::nullptr_t);
template <typename Arg> template <typename Arg>
void sendToReceiver(int fnum, const Arg &args, std::nullptr_t) const; void sendToReceiver(const int rxIndex, int fnum, const Arg &args,
std::nullptr_t) const;
template <typename Ret> template <typename Ret>
void sendToReceiver(int fnum, std::nullptr_t, Ret &retval); void sendToReceiver(const int rxIndex, int fnum, std::nullptr_t,
Ret &retval);
template <typename Ret> template <typename Ret>
void sendToReceiver(int fnum, std::nullptr_t, Ret &retval) const; void sendToReceiver(const int rxIndex, int fnum, std::nullptr_t,
Ret &retval) const;
template <typename Ret> Ret sendToReceiver(int fnum); template <typename Ret> Ret sendToReceiver(const int rxIndex, int fnum);
template <typename Ret> Ret sendToReceiver(int fnum) const; template <typename Ret>
Ret sendToReceiver(const int rxIndex, int fnum) const;
void sendToReceiver(int fnum); void sendToReceiver(const int rxIndex, int fnum);
void sendToReceiver(int fnum) const; void sendToReceiver(const int rxIndex, int fnum) const;
template <typename Ret, typename Arg> template <typename Ret, typename Arg>
Ret sendToReceiver(int fnum, const Arg &args); Ret sendToReceiver(const int rxIndex, int fnum, const Arg &args);
template <typename Ret, typename Arg> template <typename Ret, typename Arg>
Ret sendToReceiver(int fnum, const Arg &args) const; Ret sendToReceiver(const int rxIndex, int fnum, const Arg &args) const;
/** Get Detector Type from Shared Memory /** Get Detector Type from Shared Memory
verify is if shm size matches existing one */ verify is if shm size matches existing one */
@ -726,7 +743,7 @@ class Module : public virtual slsDetectorDefs {
void checkReceiverVersionCompatibility(); void checkReceiverVersionCompatibility();
void setModule(sls_detector_module &module, bool trimbits = true); void setModule(sls_detector_module &module, bool trimbits = true);
int sendModule(sls_detector_module *myMod, sls::ClientSocket &client); int sendModule(sls_detector_module *myMod, sls::ClientSocket &client);
void updateReceiverStreamingIP(); void updateReceiverStreamingIP(const int rxIndex);
void updateRateCorrection(); void updateRateCorrection();
/** Template function to do linear interpolation between two points (Eiger /** Template function to do linear interpolation between two points (Eiger
@ -761,8 +778,7 @@ class Module : public virtual slsDetectorDefs {
bool trimbits = true); bool trimbits = true);
void sendProgram(bool blackfin, std::vector<char> buffer, void sendProgram(bool blackfin, std::vector<char> buffer,
const int functionEnum, const std::string &functionType, const int functionEnum, const std::string &functionType,
const std::string serverName = "", const std::string serverName = "");
const bool forceDeleteNormalFile = false);
void simulatingActivityinDetector(const std::string &functionType, void simulatingActivityinDetector(const std::string &functionType,
const int timeRequired); const int timeRequired);

View File

@ -13,13 +13,13 @@
#include "sls/logger.h" #include "sls/logger.h"
#include "sls/sls_detector_exceptions.h" #include "sls/sls_detector_exceptions.h"
// #include "stdlib.h" #include "stdlib.h"
#include <cstdlib>
#include <cerrno> // errno #include <cerrno> // errno
#include <cstring> // strerror #include <cstring> // strerror
#include <fcntl.h> // O_CREAT, O_TRUNC.. #include <fcntl.h> // O_CREAT, O_TRUNC..
#include <iostream> #include <iostream>
#include <sstream> #include <sstream>
// #include <stdio.h> // printf
#include <sys/mman.h> // shared memory #include <sys/mman.h> // shared memory
#include <sys/stat.h> // fstat #include <sys/stat.h> // fstat
#include <unistd.h> #include <unistd.h>
@ -34,178 +34,275 @@
namespace sls { namespace sls {
template <typename T> class SharedMemory { template <typename T> class SharedMemory {
static constexpr int NAME_MAX_LENGTH = 255;
std::string name;
T *shared_struct{};
public: public:
// moduleid of -1 creates a detector only shared memory /**
SharedMemory(int detectorId, int moduleIndex, const std::string &tag = "") { * moduleid of -1 creates a detector only shared memory
name = constructSharedMemoryName(detectorId, moduleIndex, tag); */
SharedMemory(int detectorId, int moduleIndex) {
name = ConstructSharedMemoryName(detectorId, moduleIndex);
} }
// Disable copy, since we refer to a unique location /**
* Delete the copy constructor and copy assignment since we don't want two
* objects managing the same resource
*/
SharedMemory(const SharedMemory &) = delete; SharedMemory(const SharedMemory &) = delete;
SharedMemory &operator=(const SharedMemory &other) = delete; SharedMemory &operator=(const SharedMemory &other) = delete;
// Move constructor
SharedMemory(SharedMemory &&other) SharedMemory(SharedMemory &&other)
: name(other.name), shared_struct(other.shared_struct) { : name(other.name), fd(other.fd), shmSize(other.shmSize),
shared_struct(other.shared_struct) {
other.fd = -1;
other.shared_struct = nullptr; other.shared_struct = nullptr;
other.shmSize = 0;
} }
// Move assignment
SharedMemory &operator=(SharedMemory &&other) { SharedMemory &operator=(SharedMemory &&other) {
name = other.name; name = other.name;
if (shared_struct != nullptr) if (fd) {
unmapSharedMemory(); close(fd);
}
fd = other.fd;
other.fd = -1;
if (shared_struct != nullptr) {
UnmapSharedMemory();
}
shared_struct = other.shared_struct; shared_struct = other.shared_struct;
other.shared_struct = nullptr; other.shared_struct = nullptr;
shmSize = other.shmSize;
other.shmSize = 0;
return *this; return *this;
} }
~SharedMemory() { ~SharedMemory() {
if (shared_struct) if (fd >= 0)
unmapSharedMemory(); close(fd);
if (shared_struct) {
UnmapSharedMemory();
}
} }
T *operator()() { return shared_struct; } /**
const T *operator()() const { return shared_struct; } * Verify if it exists
std::string getName() const { return name; } * @return true if exists, else false
*/
bool exists() { bool IsExisting() {
bool ret = true;
int tempfd = shm_open(name.c_str(), O_RDWR, 0); int tempfd = shm_open(name.c_str(), O_RDWR, 0);
if ((tempfd < 0) && (errno == ENOENT)) { if ((tempfd < 0) && (errno == ENOENT)) {
return false; ret = false;
} }
close(tempfd); close(tempfd);
return true; return ret;
} }
void createSharedMemory() { /**
int fd = shm_open(name.c_str(), O_CREAT | O_TRUNC | O_EXCL | O_RDWR, * Get shared memory name
*/
std::string GetName() const { return name; }
size_t size() const { return shmSize; }
/**
* Create Shared memory and call MapSharedMemory to map it to an address
* throws a SharedMemoryError exception on failure to create, ftruncate or
* map
*/
void CreateSharedMemory() {
fd = shm_open(name.c_str(), O_CREAT | O_TRUNC | O_EXCL | O_RDWR,
S_IRUSR | S_IWUSR); S_IRUSR | S_IWUSR);
if (fd < 0) { if (fd < 0) {
std::string msg = std::string msg =
"Create shared memory " + name + " failed: " + strerror(errno); "Create shared memory " + name + " failed: " + strerror(errno);
LOG(logERROR) << msg;
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
if (ftruncate(fd, sizeof(T)) < 0) { if (ftruncate(fd, sizeof(T)) < 0) {
std::string msg = "Create shared memory " + name + std::string msg = "Create shared memory " + name +
" failed at ftruncate: " + strerror(errno); " failed at ftruncate: " + strerror(errno);
LOG(logERROR) << msg;
close(fd); close(fd);
removeSharedMemory(); RemoveSharedMemory();
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
shared_struct = mapSharedMemory(fd);
new (shared_struct) T{}; shared_struct = MapSharedMemory();
LOG(logINFO) << "Shared memory created " << name; LOG(logINFO) << "Shared memory created " << name;
} }
void openSharedMemory() { /**
int fd = shm_open(name.c_str(), O_RDWR, 0); * Open existing Shared memory and call MapSharedMemory to map it to an
* address throws a SharedMemoryError exception on failure to open or map
*/
void OpenSharedMemory() {
fd = shm_open(name.c_str(), O_RDWR, 0);
if (fd < 0) { if (fd < 0) {
std::string msg = "Open existing shared memory " + name + std::string msg = "Open existing shared memory " + name +
" failed: " + strerror(errno); " failed: " + strerror(errno);
LOG(logERROR) << msg;
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
checkSize(fd);
shared_struct = mapSharedMemory(fd); shared_struct = MapSharedMemory();
} }
void unmapSharedMemory() { /**
* Unmap shared memory from an address
* throws a SharedMemoryError exception on failure
*/
void UnmapSharedMemory() {
if (shared_struct != nullptr) { if (shared_struct != nullptr) {
if (munmap(shared_struct, sizeof(T)) < 0) { if (munmap(shared_struct, shmSize) < 0) {
std::string msg = "Unmapping shared memory " + name + std::string msg = "Unmapping shared memory " + name +
" failed: " + strerror(errno); " failed: " + strerror(errno);
LOG(logERROR) << msg;
close(fd);
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
shared_struct = nullptr; shared_struct = nullptr;
} }
} }
void removeSharedMemory() { /**
unmapSharedMemory(); * Remove existing Shared memory
*/
void RemoveSharedMemory() {
UnmapSharedMemory();
if (shm_unlink(name.c_str()) < 0) { if (shm_unlink(name.c_str()) < 0) {
// silent exit if shm did not exist anyway // silent exit if shm did not exist anyway
if (errno == ENOENT) if (errno == ENOENT)
return; return;
std::string msg = std::string msg =
"Free Shared Memory " + name + " Failed: " + strerror(errno); "Free Shared Memory " + name + " Failed: " + strerror(errno);
LOG(logERROR) << msg;
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
LOG(logINFO) << "Shared memory deleted " << name; LOG(logINFO) << "Shared memory deleted " << name;
} }
private: /**
std::string constructSharedMemoryName(int detectorId, int moduleIndex, * Maximum length of name as from man pages
const std::string &tag) { */
static const int NAME_MAX_LENGTH = 255;
// using environment variable /**
std::string slsdetname; *Using the call operator to access the pointer
*/
T *operator()() { return shared_struct; }
/**
*Using the call operator to access the pointer, const overload
*/
const T *operator()() const { return shared_struct; }
private:
/**
* Create Shared memory name
* throws exception if name created is longer than required 255(manpages)
* @param detectorId detector id
* @param moduleIndex module id, -1 if a detector shared memory
* @returns shared memory name
*/
std::string ConstructSharedMemoryName(int detectorId, int moduleIndex) {
// using environment path
std::string sEnvPath;
char *envpath = getenv(SHM_ENV_NAME); char *envpath = getenv(SHM_ENV_NAME);
if (envpath != nullptr) { if (envpath != nullptr) {
slsdetname = envpath; sEnvPath.assign(envpath);
slsdetname.insert(0, "_"); sEnvPath.insert(0, "_");
} }
std::stringstream ss; std::stringstream ss;
if (moduleIndex < 0) { if (moduleIndex < 0)
ss << SHM_DETECTOR_PREFIX << detectorId << slsdetname; ss << SHM_DETECTOR_PREFIX << detectorId << sEnvPath;
if (!tag.empty()) else
ss << "_" << tag;
} else {
ss << SHM_DETECTOR_PREFIX << detectorId << SHM_MODULE_PREFIX ss << SHM_DETECTOR_PREFIX << detectorId << SHM_MODULE_PREFIX
<< moduleIndex << slsdetname; << moduleIndex << sEnvPath;
}
std::string shm_name = ss.str(); std::string temp = ss.str();
if (shm_name.length() > NAME_MAX_LENGTH) { if (temp.length() > NAME_MAX_LENGTH) {
std::string msg = std::string msg =
"Shared memory initialization failed. " + shm_name + " has " + "Shared memory initialization failed. " + temp + " has " +
std::to_string(shm_name.length()) + " characters. \n" + std::to_string(temp.length()) + " characters. \n" +
"Maximum is " + std::to_string(NAME_MAX_LENGTH) + "Maximum is " + std::to_string(NAME_MAX_LENGTH) +
". Change the environment variable " + SHM_ENV_NAME; ". Change the environment variable " + SHM_ENV_NAME;
LOG(logERROR) << msg;
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
return shm_name; return temp;
} }
// from the Linux manual: /**
// After the mmap() call has returned, the file descriptor, fd, can * Map shared memory to an address
// be closed immediately without invalidating the mapping. * throws a SharedMemoryException exception on failure
T *mapSharedMemory(int fd) { */
T *MapSharedMemory() {
void *addr = void *addr =
mmap(nullptr, sizeof(T), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0); mmap(nullptr, sizeof(T), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0);
close(fd);
if (addr == MAP_FAILED) { if (addr == MAP_FAILED) {
std::string msg = std::string msg =
"Mapping shared memory " + name + " failed: " + strerror(errno); "Mapping shared memory " + name + " failed: " + strerror(errno);
LOG(logERROR) << msg;
close(fd);
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
return static_cast<T *>(addr); shmSize = sizeof(T);
close(fd);
return (T *)addr;
} }
void checkSize(int fd) { /**
* Verify if existing shared memory size matches expected size
* @param expectedSize expected size of shared memory, replaced with smaller
* size if size does not match
* @return 0 for success, 1 for fail
*/
int VerifySizeMatch(size_t expectedSize) {
struct stat sb; struct stat sb;
// could not fstat
if (fstat(fd, &sb) < 0) { if (fstat(fd, &sb) < 0) {
std::string msg = "Could not verify existing shared memory " + std::string msg = "Could not verify existing shared memory " +
name + " size match " + name + " size match " +
"(could not fstat): " + strerror(errno); "(could not fstat): " + strerror(errno);
LOG(logERROR) << msg;
close(fd); close(fd);
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
} }
auto actual_size = static_cast<size_t>(sb.st_size); // size does not match
auto expected_size = sizeof(T); auto sz = static_cast<size_t>(sb.st_size);
if (actual_size != expected_size) { if (sz != expectedSize) {
std::string msg = std::string msg = "Existing shared memory " + name +
"Existing shared memory " + name + " size does not match. " + " size does not match" + "Expected " +
"Expected " + std::to_string(expected_size) + ", found " + std::to_string(expectedSize) + ", found " +
std::to_string(actual_size) + std::to_string(sz);
". Detector software mismatch? Try freeing shared memory."; LOG(logERROR) << msg;
throw SharedMemoryError(msg); throw SharedMemoryError(msg);
return 1;
} }
return 0;
} }
/** Shared memory name */
std::string name;
/** File descriptor */
int fd{-1};
/** shm size */
size_t shmSize{0};
T *shared_struct{nullptr};
}; };
} // namespace sls } // namespace sls

View File

@ -18,7 +18,6 @@ target_sources(tests PRIVATE
${CMAKE_CURRENT_SOURCE_DIR}/test-CmdParser.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test-CmdParser.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test-Module.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test-Module.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test-Pattern.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test-Pattern.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test-CtbConfig.cpp
) )
target_include_directories(tests PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/../src>") target_include_directories(tests PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/../src>")

View File

@ -93,19 +93,13 @@ TEST_CASE("rx_framescaught", "[.cmd][.rx]") {
CmdProxy proxy(&det); CmdProxy proxy(&det);
// This ensures 0 caught frames // This ensures 0 caught frames
auto prev_val = det.getFileWrite();
det.setFileWrite(false); // avoid writing or error on file creation det.setFileWrite(false); // avoid writing or error on file creation
det.startReceiver(); det.startReceiver();
det.stopReceiver(); det.stopReceiver();
{ {
std::ostringstream oss; std::ostringstream oss;
proxy.Call("rx_framescaught", {}, -1, GET, oss); proxy.Call("rx_framescaught", {}, -1, GET, oss);
if (det.getNumberofUDPInterfaces().tsquash( REQUIRE(oss.str() == "rx_framescaught 0\n");
"inconsistent number of interfaces") == 1) {
REQUIRE(oss.str() == "rx_framescaught [0]\n");
} else {
REQUIRE(oss.str() == "rx_framescaught [0, 0]\n");
}
} }
// Currently disabled may activate if we have a stable env // Currently disabled may activate if we have a stable env
@ -117,15 +111,10 @@ TEST_CASE("rx_framescaught", "[.cmd][.rx]") {
// proxy.Call("rx_framescaught", {}, -1, GET, oss); // proxy.Call("rx_framescaught", {}, -1, GET, oss);
// REQUIRE(oss.str() == "rx_framescaught 1\n"); // REQUIRE(oss.str() == "rx_framescaught 1\n");
// } // }
for (int i = 0; i != det.size(); ++i) {
det.setFileWrite(prev_val[i], {i});
}
} }
TEST_CASE("rx_missingpackets", "[.cmd][.rx]") { TEST_CASE("rx_missingpackets", "[.cmd][.rx]") {
Detector det; Detector det;
auto prev_val = det.getFileWrite();
det.setFileWrite(false); // avoid writing or error on file creation det.setFileWrite(false); // avoid writing or error on file creation
CmdProxy proxy(&det); CmdProxy proxy(&det);
{ {
@ -134,12 +123,8 @@ TEST_CASE("rx_missingpackets", "[.cmd][.rx]") {
det.stopReceiver(); det.stopReceiver();
std::ostringstream oss; std::ostringstream oss;
proxy.Call("rx_missingpackets", {}, -1, GET, oss); proxy.Call("rx_missingpackets", {}, -1, GET, oss);
if (det.getNumberofUDPInterfaces().tsquash( std::string s = (oss.str()).erase(0, strlen("rx_missingpackets ["));
"inconsistent number of interfaces") == 1) { REQUIRE(std::stoi(s) > 0);
REQUIRE(oss.str() != "rx_missingpackets [0]\n");
} else {
REQUIRE(oss.str() != "rx_missingpackets [0, 0]\n");
}
} }
{ {
// 0 missing packets (takes into account that acquisition is stopped) // 0 missing packets (takes into account that acquisition is stopped)
@ -148,26 +133,10 @@ TEST_CASE("rx_missingpackets", "[.cmd][.rx]") {
det.stopReceiver(); det.stopReceiver();
std::ostringstream oss; std::ostringstream oss;
proxy.Call("rx_missingpackets", {}, -1, GET, oss); proxy.Call("rx_missingpackets", {}, -1, GET, oss);
if (det.getNumberofUDPInterfaces().tsquash( std::string s = (oss.str()).erase(0, strlen("rx_missingpackets ["));
"inconsistent number of interfaces") == 1) { REQUIRE(std::stoi(s) == 0);
REQUIRE(oss.str() == "rx_missingpackets [0]\n");
} else {
REQUIRE(oss.str() == "rx_missingpackets [0, 0]\n");
} }
} }
for (int i = 0; i != det.size(); ++i) {
det.setFileWrite(prev_val[i], {i});
}
}
TEST_CASE("rx_frameindex", "[.cmd][.rx]") {
Detector det;
CmdProxy proxy(&det);
proxy.Call("rx_frameindex", {}, -1, GET);
// This is a get only command
REQUIRE_THROWS(proxy.Call("rx_frameindex", {"2"}, -1, PUT));
}
/* Network Configuration (Detector<->Receiver) */ /* Network Configuration (Detector<->Receiver) */
@ -915,3 +884,16 @@ TEST_CASE("rx_jsonpara", "[.cmd][.rx]") {
} }
/* Insignificant */ /* Insignificant */
TEST_CASE("rx_frameindex", "[.cmd][.rx]") {
Detector det;
CmdProxy proxy(&det);
proxy.Call("rx_frameindex", {}, -1, GET);
// This is a get only command
REQUIRE_THROWS(proxy.Call("rx_frameindex", {"2"}, -1, PUT));
std::ostringstream oss;
proxy.Call("rx_frameindex", {}, 0, GET, oss);
std::string s = (oss.str()).erase(0, strlen("rx_frameindex "));
REQUIRE(std::stoi(s) >= 0);
}

View File

@ -590,13 +590,13 @@ TEST_CASE("master", "[.cmd]") {
} }
{ {
std::ostringstream oss1; std::ostringstream oss1;
proxy.Call("master", {"0"}, 0, PUT, oss1); proxy.Call("master", {"0"}, 0, PUT, oss3);
REQUIRE(oss1.str() == "master 0\n"); REQUIRE(oss3.str() == "master 0\n");
} }
{ {
std::ostringstream oss1; std::ostringstream oss1;
proxy.Call("master", {"1"}, 0, PUT, oss1); proxy.Call("master", {"1"}, 0, PUT, oss3);
REQUIRE(oss1.str() == "master 1\n"); REQUIRE(oss3.str() == "master 1\n");
} }
REQUIRE_THROWS(proxy.Call("master", {"1"}, -1, PUT)); REQUIRE_THROWS(proxy.Call("master", {"1"}, -1, PUT));
// set all to slaves, and then master // set all to slaves, and then master

View File

@ -1,59 +0,0 @@
#include "catch.hpp"
#include <string>
#include <stdlib.h>
#include "SharedMemory.h"
#include "CtbConfig.h"
using namespace sls;
#include <fstream>
TEST_CASE("Default construction"){
static_assert(sizeof(CtbConfig) == 360); // 18*20
CtbConfig c;
auto names = c.getDacNames();
REQUIRE(names.size() == 18);
REQUIRE(names[0] == "dac0");
REQUIRE(names[1] == "dac1");
REQUIRE(names[2] == "dac2");
REQUIRE(names[3] == "dac3");
}
TEST_CASE("Set and get a single dac name"){
CtbConfig c;
c.setDacName(3, "vrf");
auto names = c.getDacNames();
REQUIRE(c.getDacName(3) == "vrf");
REQUIRE(names[3] == "vrf");
}
TEST_CASE("Set a name that is too large throws"){
CtbConfig c;
REQUIRE_THROWS(c.setDacName(3, "somestringthatisreallytolongforadatac"));
}
TEST_CASE("Length of dac name cannot be 0"){
CtbConfig c;
REQUIRE_THROWS(c.setDacName(1, ""));
}
TEST_CASE("Copy a CTB config"){
CtbConfig c1;
c1.setDacName(5, "somename");
auto c2 = c1;
//change the name on the first object
//to detecto shallow copy
c1.setDacName(5, "someothername");
REQUIRE(c2.getDacName(5) == "somename");
}
TEST_CASE("Move CtbConfig "){
CtbConfig c1;
c1.setDacName(3, "yetanothername");
CtbConfig c2(std::move(c1));
REQUIRE(c2.getDacName(3) == "yetanothername");
}

View File

@ -32,8 +32,8 @@ TEST_CASE("Is shm fixed pattern shm compatible") {
// Set shm version to 0 // Set shm version to 0
sls::SharedMemory<sls::sharedModule> shm(0, 0); sls::SharedMemory<sls::sharedModule> shm(0, 0);
REQUIRE(shm.exists() == true); REQUIRE(shm.IsExisting() == true);
shm.openSharedMemory(); shm.OpenSharedMemory();
shm()->shmversion = 0; shm()->shmversion = 0;
// Should fail since version is set to 0 // Should fail since version is set to 0

View File

@ -20,8 +20,8 @@ constexpr int shm_id = 10;
TEST_CASE("Create SharedMemory read and write", "[detector]") { TEST_CASE("Create SharedMemory read and write", "[detector]") {
SharedMemory<Data> shm(shm_id, -1); SharedMemory<Data> shm(shm_id, -1);
shm.createSharedMemory(); shm.CreateSharedMemory();
CHECK(shm.getName() == std::string("/slsDetectorPackage_detector_") + CHECK(shm.GetName() == std::string("/slsDetectorPackage_detector_") +
std::to_string(shm_id)); std::to_string(shm_id));
shm()->x = 3; shm()->x = 3;
@ -32,25 +32,25 @@ TEST_CASE("Create SharedMemory read and write", "[detector]") {
CHECK(shm()->y == 5.7); CHECK(shm()->y == 5.7);
CHECK(std::string(shm()->mess) == "Some string"); CHECK(std::string(shm()->mess) == "Some string");
shm.unmapSharedMemory(); shm.UnmapSharedMemory();
shm.removeSharedMemory(); shm.RemoveSharedMemory();
CHECK(shm.exists() == false); CHECK(shm.IsExisting() == false);
} }
TEST_CASE("Open existing SharedMemory and read", "[detector]") { TEST_CASE("Open existing SharedMemory and read", "[detector]") {
{ {
SharedMemory<double> shm(shm_id, -1); SharedMemory<double> shm(shm_id, -1);
shm.createSharedMemory(); shm.CreateSharedMemory();
*shm() = 5.3; *shm() = 5.3;
} }
SharedMemory<double> shm2(shm_id, -1); SharedMemory<double> shm2(shm_id, -1);
shm2.openSharedMemory(); shm2.OpenSharedMemory();
CHECK(*shm2() == 5.3); CHECK(*shm2() == 5.3);
shm2.removeSharedMemory(); shm2.RemoveSharedMemory();
} }
TEST_CASE("Creating a second shared memory with the same name throws", TEST_CASE("Creating a second shared memory with the same name throws",
@ -59,24 +59,24 @@ TEST_CASE("Creating a second shared memory with the same name throws",
SharedMemory<double> shm0(shm_id, -1); SharedMemory<double> shm0(shm_id, -1);
SharedMemory<double> shm1(shm_id, -1); SharedMemory<double> shm1(shm_id, -1);
shm0.createSharedMemory(); shm0.CreateSharedMemory();
CHECK_THROWS(shm1.createSharedMemory()); CHECK_THROWS(shm1.CreateSharedMemory());
shm0.removeSharedMemory(); shm0.RemoveSharedMemory();
} }
TEST_CASE("Open two shared memories to the same place", "[detector]") { TEST_CASE("Open two shared memories to the same place", "[detector]") {
// Create the first shared memory // Create the first shared memory
SharedMemory<Data> shm(shm_id, -1); SharedMemory<Data> shm(shm_id, -1);
shm.createSharedMemory(); shm.CreateSharedMemory();
shm()->x = 5; shm()->x = 5;
CHECK(shm()->x == 5); CHECK(shm()->x == 5);
// Open the second shared memory with the same name // Open the second shared memory with the same name
SharedMemory<Data> shm2(shm_id, -1); SharedMemory<Data> shm2(shm_id, -1);
shm2.openSharedMemory(); shm2.OpenSharedMemory();
CHECK(shm2()->x == 5); CHECK(shm2()->x == 5);
CHECK(shm.getName() == shm2.getName()); CHECK(shm.GetName() == shm2.GetName());
// Check that they still point to the same place // Check that they still point to the same place
shm2()->x = 7; shm2()->x = 7;
@ -84,28 +84,31 @@ TEST_CASE("Open two shared memories to the same place", "[detector]") {
// Remove only needs to be done once since they refer // Remove only needs to be done once since they refer
// to the same memory // to the same memory
shm2.removeSharedMemory(); shm2.RemoveSharedMemory();
CHECK(shm.exists() == false); CHECK(shm.IsExisting() == false);
CHECK(shm2.exists() == false); CHECK(shm2.IsExisting() == false);
} }
TEST_CASE("Move SharedMemory", "[detector]") { TEST_CASE("Move SharedMemory", "[detector]") {
SharedMemory<Data> shm(shm_id, -1); SharedMemory<Data> shm(shm_id, -1);
CHECK(shm.getName() == std::string("/slsDetectorPackage_detector_") + CHECK(shm.GetName() == std::string("/slsDetectorPackage_detector_") +
std::to_string(shm_id)); std::to_string(shm_id));
shm.createSharedMemory(); shm.CreateSharedMemory();
shm()->x = 9; shm()->x = 9;
CHECK(shm.size() == sizeof(Data));
SharedMemory<Data> shm2(shm_id + 1, -1); SharedMemory<Data> shm2(shm_id + 1, -1);
shm2 = std::move(shm); // shm is now a moved from object! shm2 = std::move(shm); // shm is now a moved from object!
CHECK(shm2()->x == 9); CHECK(shm2()->x == 9);
CHECK(shm() == nullptr); CHECK(shm() == nullptr);
CHECK(shm2.getName() == std::string("/slsDetectorPackage_detector_") + CHECK(shm.size() == 0);
CHECK(shm2.GetName() == std::string("/slsDetectorPackage_detector_") +
std::to_string(shm_id)); std::to_string(shm_id));
shm2.removeSharedMemory(); shm2.RemoveSharedMemory();
} }
TEST_CASE("Create several shared memories", "[detector]") { TEST_CASE("Create several shared memories", "[detector]") {
@ -114,62 +117,20 @@ TEST_CASE("Create several shared memories", "[detector]") {
v.reserve(N); v.reserve(N);
for (int i = 0; i != N; ++i) { for (int i = 0; i != N; ++i) {
v.emplace_back(shm_id + i, -1); v.emplace_back(shm_id + i, -1);
CHECK(v[i].exists() == false); CHECK(v[i].IsExisting() == false);
v[i].createSharedMemory(); v[i].CreateSharedMemory();
*v[i]() = i; *v[i]() = i;
CHECK(*v[i]() == i); CHECK(*v[i]() == i);
} }
for (int i = 0; i != N; ++i) { for (int i = 0; i != N; ++i) {
CHECK(*v[i]() == i); CHECK(*v[i]() == i);
CHECK(v[i].getName() == std::string("/slsDetectorPackage_detector_") + CHECK(v[i].GetName() == std::string("/slsDetectorPackage_detector_") +
std::to_string(i + shm_id)); std::to_string(i + shm_id));
} }
for (int i = 0; i != N; ++i) { for (int i = 0; i != N; ++i) {
v[i].removeSharedMemory(); v[i].RemoveSharedMemory();
CHECK(v[i].exists() == false); CHECK(v[i].IsExisting() == false);
} }
} }
TEST_CASE("Create create a shared memory with a tag"){
SharedMemory<int> shm(0, -1, "ctbdacs");
REQUIRE(shm.getName() == "/slsDetectorPackage_detector_0_ctbdacs");
}
TEST_CASE("Create create a shared memory with a tag when SLSDETNAME is set"){
// if SLSDETNAME is already set we unset it but
// save the value
std::string old_slsdetname;
if (getenv(SHM_ENV_NAME))
old_slsdetname = getenv(SHM_ENV_NAME);
unsetenv(SHM_ENV_NAME);
setenv(SHM_ENV_NAME, "myprefix", 1);
SharedMemory<int> shm(0, -1, "ctbdacs");
REQUIRE(shm.getName() == "/slsDetectorPackage_detector_0_myprefix_ctbdacs");
// Clean up after us
if (old_slsdetname.empty())
unsetenv(SHM_ENV_NAME);
else
setenv(SHM_ENV_NAME, old_slsdetname.c_str(), 1);
}
TEST_CASE("map int64 to int32 throws"){
SharedMemory<int32_t> shm(shm_id, -1);
shm.createSharedMemory();
*shm() = 7;
SharedMemory<int64_t> shm2(shm_id, -1);
REQUIRE_THROWS(shm2.openSharedMemory());
shm.removeSharedMemory();
}

View File

@ -6,6 +6,7 @@ set(SOURCES
src/Receiver.cpp src/Receiver.cpp
src/File.cpp src/File.cpp
src/BinaryDataFile.cpp src/BinaryDataFile.cpp
src/BinaryMasterFile.cpp
src/ThreadObject.cpp src/ThreadObject.cpp
src/Listener.cpp src/Listener.cpp
src/DataProcessor.cpp src/DataProcessor.cpp
@ -13,7 +14,6 @@ set(SOURCES
src/Fifo.cpp src/Fifo.cpp
src/Arping.cpp src/Arping.cpp
src/MasterAttributes.cpp src/MasterAttributes.cpp
src/MasterFileUtility.cpp
) )
set(PUBLICHEADERS set(PUBLICHEADERS
@ -28,6 +28,8 @@ if (SLS_USE_HDF5)
) )
list (APPEND SOURCES list (APPEND SOURCES
src/HDF5DataFile.cpp src/HDF5DataFile.cpp
src/HDF5MasterFile.cpp
src/HDF5VirtualFile.cpp
) )
endif (SLS_USE_HDF5) endif (SLS_USE_HDF5)

View File

@ -72,7 +72,7 @@ void BinaryDataFile::WriteToFile(char *buffer, const int buffersize,
++subFileIndex_; ++subFileIndex_;
CreateFile(); CreateFile();
} }
++numFramesInFile_; numFramesInFile_++;
// write to file // write to file
int ret = 0; int ret = 0;

View File

@ -0,0 +1,60 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#include "BinaryMasterFile.h"
#include "MasterAttributes.h"
BinaryMasterFile::BinaryMasterFile() : File(BINARY) {}
BinaryMasterFile::~BinaryMasterFile() { CloseFile(); }
void BinaryMasterFile::CloseFile() {
if (fd_) {
fclose(fd_);
}
fd_ = nullptr;
}
void BinaryMasterFile::CreateMasterFile(const std::string filePath,
const std::string fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr) {
// create file name
std::ostringstream os;
os << filePath << "/" << fileNamePrefix << "_master"
<< "_" << fileIndex << ".raw";
fileName_ = os.str();
// create file
if (!overWriteEnable) {
if (nullptr == (fd_ = fopen((const char *)fileName_.c_str(), "wx"))) {
fd_ = nullptr;
throw sls::RuntimeError("Could not create binary master file " +
fileName_);
}
} else if (nullptr == (fd_ = fopen((const char *)fileName_.c_str(), "w"))) {
fd_ = nullptr;
throw sls::RuntimeError(
"Could not create/overwrite binary master file " + fileName_);
}
if (!silentMode) {
LOG(logINFO) << "Master File: " << fileName_;
}
attr->WriteMasterBinaryAttributes(fd_);
CloseFile();
}
void BinaryMasterFile::UpdateMasterFile(MasterAttributes *attr,
bool silentMode) {
if (nullptr == (fd_ = fopen((const char *)fileName_.c_str(), "a"))) {
fd_ = nullptr;
throw sls::RuntimeError("Could not append binary master file " +
fileName_);
}
attr->WriteFinalBinaryAttributes(fd_);
CloseFile();
if (!silentMode) {
LOG(logINFO) << "Updated Master File";
}
}

View File

@ -0,0 +1,25 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#pragma once
#include "File.h"
#include "MasterAttributes.h"
class BinaryMasterFile : private virtual slsDetectorDefs, public File {
public:
BinaryMasterFile();
~BinaryMasterFile();
void CloseFile() override;
void CreateMasterFile(const std::string filePath,
const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr) override;
void UpdateMasterFile(MasterAttributes *attr, bool silentMode) override;
private:
FILE *fd_{nullptr};
std::string fileName_;
};

View File

@ -848,13 +848,9 @@ int ClientInterface::get_file_index(Interface &socket) {
} }
int ClientInterface::get_frame_index(Interface &socket) { int ClientInterface::get_frame_index(Interface &socket) {
auto retval = impl()->getCurrentFrameIndex(); uint64_t retval = impl()->getCurrentFrameIndex();
LOG(logDEBUG1) << "frames index:" << sls::ToString(retval); LOG(logDEBUG1) << "frame index:" << retval;
auto size = static_cast<int>(retval.size()); return socket.sendResult(retval);
socket.Send(OK);
socket.Send(size);
socket.Send(retval);
return OK;
} }
int ClientInterface::get_missing_packets(Interface &socket) { int ClientInterface::get_missing_packets(Interface &socket) {
@ -868,13 +864,9 @@ int ClientInterface::get_missing_packets(Interface &socket) {
} }
int ClientInterface::get_frames_caught(Interface &socket) { int ClientInterface::get_frames_caught(Interface &socket) {
auto retval = impl()->getFramesCaught(); int64_t retval = impl()->getFramesCaught();
LOG(logDEBUG1) << "frames caught:" << sls::ToString(retval); LOG(logDEBUG1) << "frames caught:" << retval;
auto size = static_cast<int>(retval.size()); return socket.sendResult(retval);
socket.Send(OK);
socket.Send(size);
socket.Send(retval);
return OK;
} }
int ClientInterface::set_file_write(Interface &socket) { int ClientInterface::set_file_write(Interface &socket) {

View File

@ -9,12 +9,14 @@
#include "DataProcessor.h" #include "DataProcessor.h"
#include "BinaryDataFile.h" #include "BinaryDataFile.h"
#include "BinaryMasterFile.h"
#include "Fifo.h" #include "Fifo.h"
#include "GeneralData.h" #include "GeneralData.h"
#include "MasterAttributes.h" #include "MasterAttributes.h"
#include "MasterFileUtility.h"
#ifdef HDF5C #ifdef HDF5C
#include "HDF5DataFile.h" #include "HDF5DataFile.h"
#include "HDF5MasterFile.h"
#include "HDF5VirtualFile.h"
#endif #endif
#include "DataStreamer.h" #include "DataStreamer.h"
#include "sls/container_utils.h" #include "sls/container_utils.h"
@ -50,7 +52,19 @@ DataProcessor::~DataProcessor() { DeleteFiles(); }
/** getters */ /** getters */
bool DataProcessor::GetStartedFlag() const { return startedFlag_; } bool DataProcessor::GetStartedFlag() { return startedFlag_; }
uint64_t DataProcessor::GetNumFramesCaught() { return numFramesCaught_; }
uint64_t DataProcessor::GetNumCompleteFramesCaught() {
return numCompleteFramesCaught_;
}
uint64_t DataProcessor::GetCurrentFrameIndex() { return currentFrameIndex_; }
uint64_t DataProcessor::GetProcessedIndex() {
return currentFrameIndex_ - firstIndex_;
}
void DataProcessor::SetFifo(Fifo *fifo) { fifo_ = fifo; } void DataProcessor::SetFifo(Fifo *fifo) { fifo_ = fifo; }
@ -58,6 +72,7 @@ void DataProcessor::ResetParametersforNewAcquisition() {
StopRunning(); StopRunning();
startedFlag_ = false; startedFlag_ = false;
numFramesCaught_ = 0; numFramesCaught_ = 0;
numCompleteFramesCaught_ = 0;
firstIndex_ = 0; firstIndex_ = 0;
currentFrameIndex_ = 0; currentFrameIndex_ = 0;
firstStreamerFrame_ = true; firstStreamerFrame_ = true;
@ -80,6 +95,12 @@ void DataProcessor::SetGeneralData(GeneralData *generalData) {
void DataProcessor::CloseFiles() { void DataProcessor::CloseFiles() {
if (dataFile_) if (dataFile_)
dataFile_->CloseFile(); dataFile_->CloseFile();
if (masterFile_)
masterFile_->CloseFile();
#ifdef HDF5C
if (virtualFile_)
virtualFile_->CloseFile();
#endif
} }
void DataProcessor::DeleteFiles() { void DataProcessor::DeleteFiles() {
@ -88,20 +109,39 @@ void DataProcessor::DeleteFiles() {
delete dataFile_; delete dataFile_;
dataFile_ = nullptr; dataFile_ = nullptr;
} }
if (masterFile_) {
delete masterFile_;
masterFile_ = nullptr;
}
#ifdef HDF5C
if (virtualFile_) {
delete virtualFile_;
virtualFile_ = nullptr;
}
#endif
} }
void DataProcessor::SetupFileWriter(const bool filewriteEnable, void DataProcessor::SetupFileWriter(const bool filewriteEnable,
const bool masterFilewriteEnable,
const fileFormat fileFormatType, const fileFormat fileFormatType,
std::mutex *hdf5LibMutex) { const int modulePos, std::mutex *hdf5Lib) {
DeleteFiles(); DeleteFiles();
if (filewriteEnable) { if (filewriteEnable) {
switch (fileFormatType) { switch (fileFormatType) {
#ifdef HDF5C #ifdef HDF5C
case HDF5: case HDF5:
dataFile_ = new HDF5DataFile(index, hdf5LibMutex); dataFile_ = new HDF5DataFile(index, hdf5Lib);
if (modulePos == 0 && index == 0) {
if (masterFilewriteEnable) {
masterFile_ = new HDF5MasterFile(hdf5Lib);
}
}
break; break;
#endif #endif
case BINARY: case BINARY:
dataFile_ = new BinaryDataFile(index); dataFile_ = new BinaryDataFile(index);
if (modulePos == 0 && index == 0 && masterFilewriteEnable) {
masterFile_ = new BinaryMasterFile();
}
break; break;
default: default:
throw sls::RuntimeError( throw sls::RuntimeError(
@ -111,17 +151,23 @@ void DataProcessor::SetupFileWriter(const bool filewriteEnable,
} }
void DataProcessor::CreateFirstFiles( void DataProcessor::CreateFirstFiles(
const std::string &filePath, const std::string &fileNamePrefix, MasterAttributes *attr, const std::string filePath,
const uint64_t fileIndex, const bool overWriteEnable, const bool silentMode, const std::string fileNamePrefix, const uint64_t fileIndex,
const int modulePos, const int numUnitsPerReadout, const bool overWriteEnable, const bool silentMode, const int modulePos,
const uint32_t udpPortNumber, const uint32_t maxFramesPerFile, const int numUnitsPerReadout, const uint32_t udpPortNumber,
const uint64_t numImages, const uint32_t dynamicRange, const uint32_t maxFramesPerFile, const uint64_t numImages,
const bool detectorDataStream) { const uint32_t dynamicRange, const bool detectorDataStream) {
if (dataFile_ == nullptr) { if (dataFile_ == nullptr) {
throw sls::RuntimeError("file object not contstructed"); throw sls::RuntimeError("file object not contstructed");
} }
CloseFiles(); CloseFiles();
// master file write enabled
if (masterFile_) {
masterFile_->CreateMasterFile(filePath, fileNamePrefix, fileIndex,
overWriteEnable, silentMode, attr);
}
// deactivated (half module/ single port), dont write file // deactivated (half module/ single port), dont write file
if ((!*activated_) || (!detectorDataStream)) { if ((!*activated_) || (!detectorDataStream)) {
return; return;
@ -156,75 +202,85 @@ uint32_t DataProcessor::GetFilesInAcquisition() const {
return dataFile_->GetFilesInAcquisition(); return dataFile_->GetFilesInAcquisition();
} }
std::array<std::string, 2> DataProcessor::CreateVirtualFile( void DataProcessor::CreateVirtualFile(
const std::string &filePath, const std::string &fileNamePrefix, const std::string filePath, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const bool silentMode, const uint64_t fileIndex, const bool overWriteEnable, const bool silentMode,
const int modulePos, const int numUnitsPerReadout, const int modulePos, const int numUnitsPerReadout,
const uint32_t maxFramesPerFile, const uint64_t numImages, const uint32_t maxFramesPerFile, const uint64_t numImages,
const int numModX, const int numModY, const uint32_t dynamicRange, const uint32_t dynamicRange, const int numModX, const int numModY,
std::mutex *hdf5LibMutex) { std::mutex *hdf5Lib) {
bool gotthard25um = if (virtualFile_) {
((detectorType_ == GOTTHARD || detectorType_ == GOTTHARD2) && delete virtualFile_;
(numModX * numModY) == 2); }
virtualFile_ = new HDF5VirtualFile(hdf5Lib);
uint64_t numImagesProcessed = GetProcessedIndex() + 1;
// maxframesperfile = 0 for infinite files // maxframesperfile = 0 for infinite files
uint32_t framesPerFile = uint32_t framesPerFile =
((maxFramesPerFile == 0) ? numFramesCaught_ : maxFramesPerFile); ((maxFramesPerFile == 0) ? numImagesProcessed + 1 : maxFramesPerFile);
// TODO: assumption 1: create virtual file even if no data in other // TODO: assumption 1: create virtual file even if no data in other
// files (they exist anyway) assumption2: virtual file max frame index // files (they exist anyway) assumption2: virtual file max frame index
// is from R0 P0 (difference from others when missing frames or for a // is from R0 P0 (difference from others when missing frames or for a
// stop acquisition) // stop acquisition)
return masterFileUtility::CreateVirtualHDF5File( virtualFile_->CreateVirtualFile(
filePath, fileNamePrefix, fileIndex, overWriteEnable, silentMode, filePath, fileNamePrefix, fileIndex, overWriteEnable, silentMode,
modulePos, numUnitsPerReadout, framesPerFile, numImages, modulePos, numUnitsPerReadout, framesPerFile, numImages,
generalData_->nPixelsX, generalData_->nPixelsY, dynamicRange, generalData_->nPixelsX, generalData_->nPixelsY, dynamicRange,
numFramesCaught_, numModX, numModY, dataFile_->GetPDataType(), numImagesProcessed, numModX, numModY, dataFile_->GetPDataType(),
dataFile_->GetParameterNames(), dataFile_->GetParameterDataTypes(), dataFile_->GetParameterNames(), dataFile_->GetParameterDataTypes());
hdf5LibMutex, gotthard25um);
} }
void DataProcessor::LinkFileInMaster(const std::string &masterFileName, void DataProcessor::LinkDataInMasterFile(const bool silentMode) {
const std::string &virtualFileName, std::string fname, datasetName;
const std::string &virtualDatasetName, if (virtualFile_) {
const bool silentMode, auto res = virtualFile_->GetFileAndDatasetName();
std::mutex *hdf5LibMutex) { fname = res[0];
std::string fname{virtualFileName}, datasetName{virtualDatasetName}; datasetName = res[1];
// if no virtual file, link data file } else {
if (virtualFileName.empty()) {
auto res = dataFile_->GetFileAndDatasetName(); auto res = dataFile_->GetFileAndDatasetName();
fname = res[0]; fname = res[0];
datasetName = res[1]; datasetName = res[1];
} }
masterFileUtility::LinkHDF5FileInMaster(masterFileName, fname, datasetName, // link in master
dataFile_->GetParameterNames(), masterFile_->LinkDataFile(fname, datasetName,
silentMode, hdf5LibMutex); dataFile_->GetParameterNames(), silentMode);
} }
#endif #endif
std::string DataProcessor::CreateMasterFile( void DataProcessor::UpdateMasterFile(bool silentMode) {
const std::string &filePath, const std::string &fileNamePrefix, if (masterFile_) {
const uint64_t fileIndex, const bool overWriteEnable, bool silentMode, // final attributes
const fileFormat fileFormatType, MasterAttributes *attr, std::unique_ptr<MasterAttributes> masterAttributes;
std::mutex *hdf5LibMutex) { switch (detectorType_) {
case GOTTHARD:
attr->framesInFile = numFramesCaught_; masterAttributes = sls::make_unique<GotthardMasterAttributes>();
break;
std::unique_ptr<File> masterFile{nullptr}; case JUNGFRAU:
switch (fileFormatType) { masterAttributes = sls::make_unique<JungfrauMasterAttributes>();
#ifdef HDF5C break;
case HDF5: case EIGER:
return masterFileUtility::CreateMasterHDF5File( masterAttributes = sls::make_unique<EigerMasterAttributes>();
filePath, fileNamePrefix, fileIndex, overWriteEnable, silentMode, break;
attr, hdf5LibMutex); case MYTHEN3:
#endif masterAttributes = sls::make_unique<Mythen3MasterAttributes>();
case BINARY: break;
return masterFileUtility::CreateMasterBinaryFile( case GOTTHARD2:
filePath, fileNamePrefix, fileIndex, overWriteEnable, silentMode, masterAttributes = sls::make_unique<Gotthard2MasterAttributes>();
attr); break;
case MOENCH:
masterAttributes = sls::make_unique<MoenchMasterAttributes>();
break;
case CHIPTESTBOARD:
masterAttributes = sls::make_unique<CtbMasterAttributes>();
break;
default: default:
throw sls::RuntimeError("Unknown file format (compile with hdf5 flags"); throw sls::RuntimeError(
"Unknown detector type to set up master file attributes");
}
masterAttributes->framesInFile = numFramesCaught_;
masterFile_->UpdateMasterFile(masterAttributes.get(), silentMode);
} }
} }
@ -288,6 +344,9 @@ uint64_t DataProcessor::ProcessAnImage(char *buf) {
currentFrameIndex_ = fnum; currentFrameIndex_ = fnum;
numFramesCaught_++; numFramesCaught_++;
uint32_t nump = header.packetNumber; uint32_t nump = header.packetNumber;
if (nump == generalData_->packetsPerFrame) {
numCompleteFramesCaught_++;
}
LOG(logDEBUG1) << "DataProcessing " << index << ": fnum:" << fnum; LOG(logDEBUG1) << "DataProcessing " << index << ": fnum:" << fnum;

View File

@ -36,7 +36,13 @@ class DataProcessor : private virtual slsDetectorDefs, public ThreadObject {
~DataProcessor() override; ~DataProcessor() override;
bool GetStartedFlag() const; bool GetStartedFlag();
uint64_t GetNumFramesCaught();
uint64_t GetNumCompleteFramesCaught();
/** (-1 if no frames have been caught */
uint64_t GetCurrentFrameIndex();
/** (-1 if no frames have been caught) */
uint64_t GetProcessedIndex();
void SetFifo(Fifo *f); void SetFifo(Fifo *f);
void ResetParametersforNewAcquisition(); void ResetParametersforNewAcquisition();
@ -45,11 +51,12 @@ class DataProcessor : private virtual slsDetectorDefs, public ThreadObject {
void CloseFiles(); void CloseFiles();
void DeleteFiles(); void DeleteFiles();
void SetupFileWriter(const bool filewriteEnable, void SetupFileWriter(const bool filewriteEnable,
const fileFormat fileFormatType, const bool masterFilewriteEnable,
std::mutex *hdf5LibMutex); const fileFormat fileFormatType, const int modulePos,
std::mutex *hdf5Lib);
void CreateFirstFiles(const std::string &filePath, void CreateFirstFiles(MasterAttributes *attr, const std::string filePath,
const std::string &fileNamePrefix, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const uint64_t fileIndex, const bool overWriteEnable,
const bool silentMode, const int modulePos, const bool silentMode, const int modulePos,
const int numUnitsPerReadout, const int numUnitsPerReadout,
@ -59,26 +66,18 @@ class DataProcessor : private virtual slsDetectorDefs, public ThreadObject {
const bool detectorDataStream); const bool detectorDataStream);
#ifdef HDF5C #ifdef HDF5C
uint32_t GetFilesInAcquisition() const; uint32_t GetFilesInAcquisition() const;
std::array<std::string, 2> CreateVirtualFile( void CreateVirtualFile(const std::string filePath,
const std::string &filePath, const std::string &fileNamePrefix, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const uint64_t fileIndex, const bool overWriteEnable,
const bool silentMode, const int modulePos, const bool silentMode, const int modulePos,
const int numUnitsPerReadout, const uint32_t maxFramesPerFile, const int numUnitsPerReadout,
const uint64_t numImages, const int numModX, const int numModY, const uint32_t maxFramesPerFile,
const uint32_t dynamicRange, std::mutex *hdf5LibMutex); const uint64_t numImages,
void LinkFileInMaster(const std::string &masterFileName, const uint32_t dynamicRange, const int numModX,
const std::string &virtualFileName, const int numModY, std::mutex *hdf5Lib);
const std::string &virtualDatasetName, void LinkDataInMasterFile(const bool silentMode);
const bool silentMode, std::mutex *hdf5LibMutex);
#endif #endif
void UpdateMasterFile(bool silentMode);
std::string CreateMasterFile(const std::string &filePath,
const std::string &fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable, bool silentMode,
const fileFormat fileFormatType,
MasterAttributes *attr,
std::mutex *hdf5LibMutex);
/** /**
* Call back for raw data * Call back for raw data
* args to raw data ready callback are * args to raw data ready callback are
@ -179,6 +178,9 @@ class DataProcessor : private virtual slsDetectorDefs, public ThreadObject {
/** Number of frames caught */ /** Number of frames caught */
uint64_t numFramesCaught_{0}; uint64_t numFramesCaught_{0};
/** Number of complete frames caught */
uint64_t numCompleteFramesCaught_{0};
/** Frame Number of latest processed frame number */ /** Frame Number of latest processed frame number */
std::atomic<uint64_t> currentFrameIndex_{0}; std::atomic<uint64_t> currentFrameIndex_{0};
@ -186,6 +188,10 @@ class DataProcessor : private virtual slsDetectorDefs, public ThreadObject {
bool firstStreamerFrame_{false}; bool firstStreamerFrame_{false};
File *dataFile_{nullptr}; File *dataFile_{nullptr};
File *masterFile_{nullptr};
#ifdef HDF5C
File *virtualFile_{nullptr};
#endif
// call back // call back
/** /**

View File

@ -60,6 +60,20 @@ class File : private virtual slsDetectorDefs {
return std::vector<DataType>{}; return std::vector<DataType>{};
}; };
virtual void CreateVirtualFile(
const std::string filePath, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable,
const bool silentMode, const int modulePos,
const int numUnitsPerReadout, const uint32_t maxFramesPerFile,
const uint64_t numImages, const uint32_t nPixelsX,
const uint32_t nPixelsY, const uint32_t dynamicRange,
const uint64_t numImagesCaught, const int numModX, const int numModY,
const DataType dataType, const std::vector<std::string> parameterNames,
const std::vector<DataType> parameterDataTypes) {
LOG(logERROR) << "This is a generic function CreateVirtualFile that "
"should be overloaded by a derived class";
}
virtual void CreateFirstHDF5DataFile( virtual void CreateFirstHDF5DataFile(
const std::string filePath, const std::string fileNamePrefix, const std::string filePath, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const uint64_t fileIndex, const bool overWriteEnable,
@ -71,6 +85,13 @@ class File : private virtual slsDetectorDefs {
LOG(logERROR) << "This is a generic function CreateFirstDataFile that " LOG(logERROR) << "This is a generic function CreateFirstDataFile that "
"should be overloaded by a derived class"; "should be overloaded by a derived class";
}; };
virtual void LinkDataFile(std::string dataFilename, std::string dataSetname,
const std::vector<std::string> parameterNames,
const bool silentMode) {
LOG(logERROR) << "This is a generic function LinkDataFile that "
"should be overloaded by a derived class";
};
#endif #endif
virtual void CreateFirstBinaryDataFile( virtual void CreateFirstBinaryDataFile(
const std::string filePath, const std::string fileNamePrefix, const std::string filePath, const std::string fileNamePrefix,
@ -82,9 +103,27 @@ class File : private virtual slsDetectorDefs {
"should be overloaded by a derived class"; "should be overloaded by a derived class";
}; };
virtual void CreateMasterFile(const std::string filePath,
const std::string fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr) {
LOG(logERROR) << "This is a generic function CreateMasterFile that "
"should be overloaded by a derived class";
};
virtual void WriteToFile(char *buffer, const int buffersize, virtual void WriteToFile(char *buffer, const int buffersize,
const uint64_t currentFrameNumber, const uint64_t currentFrameNumber,
const uint32_t numPacketsCaught) = 0; const uint32_t numPacketsCaught) {
LOG(logERROR) << "This is a generic function WriteToFile that "
"should be overloaded by a derived class";
};
virtual void UpdateMasterFile(MasterAttributes *attr, bool silentMode) {
LOG(logERROR) << "This is a generic function UpdateMasterFile that "
"should be overloaded by a derived class";
};
protected: protected:
slsDetectorDefs::fileFormat format_; slsDetectorDefs::fileFormat format_;

View File

@ -128,7 +128,7 @@ void HDF5DataFile::CreateFirstHDF5DataFile(
} }
void HDF5DataFile::CreateFile() { void HDF5DataFile::CreateFile() {
numFramesInFile_ = 0;
numFilesInAcquisition_++; numFilesInAcquisition_++;
std::ostringstream os; std::ostringstream os;
@ -237,7 +237,7 @@ void HDF5DataFile::WriteToFile(char *buffer, const int buffersize,
++subFileIndex_; ++subFileIndex_;
CreateFile(); CreateFile();
} }
++numFramesInFile_; numFramesInFile_++;
// extend dataset (when receiver start followed by many status starts // extend dataset (when receiver start followed by many status starts
// (jungfrau))) // (jungfrau)))

View File

@ -0,0 +1,162 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#include "HDF5MasterFile.h"
#include "MasterAttributes.h"
HDF5MasterFile::HDF5MasterFile(std::mutex *hdf5Lib)
: File(HDF5), hdf5Lib_(hdf5Lib) {}
HDF5MasterFile::~HDF5MasterFile() { CloseFile(); }
void HDF5MasterFile::CloseFile() {
std::lock_guard<std::mutex> lock(*hdf5Lib_);
try {
Exception::dontPrint(); // to handle errors
if (fd_) {
fd_->close();
delete fd_;
fd_ = nullptr;
}
} catch (const Exception &error) {
LOG(logERROR) << "Could not close master HDF5 handles";
error.printErrorStack();
}
}
void HDF5MasterFile::LinkDataFile(std::string dataFilename,
std::string dataSetname,
const std::vector<std::string> parameterNames,
const bool silentMode) {
std::lock_guard<std::mutex> lock(*hdf5Lib_);
try {
Exception::dontPrint(); // to handle errors
FileAccPropList flist;
flist.setFcloseDegree(H5F_CLOSE_STRONG);
// open master file
H5File masterfd(fileName_.c_str(), H5F_ACC_RDWR,
FileCreatPropList::DEFAULT, flist);
// open data file
H5File fd(dataFilename.c_str(), H5F_ACC_RDONLY,
FileCreatPropList::DEFAULT, flist);
// create link for data dataset
DataSet dset = fd.openDataSet(dataSetname.c_str());
std::string linkname = std::string("/entry/data/") + dataSetname;
if (H5Lcreate_external(dataFilename.c_str(), dataSetname.c_str(),
masterfd.getLocId(), linkname.c_str(),
H5P_DEFAULT, H5P_DEFAULT) < 0) {
throw sls::RuntimeError(
"Could not create link to data dataset in master");
}
// create link for parameter datasets
for (unsigned int i = 0; i < parameterNames.size(); ++i) {
DataSet pDset = fd.openDataSet(parameterNames[i].c_str());
linkname = std::string("/entry/data/") + parameterNames[i];
if (H5Lcreate_external(dataFilename.c_str(),
parameterNames[i].c_str(),
masterfd.getLocId(), linkname.c_str(),
H5P_DEFAULT, H5P_DEFAULT) < 0) {
throw sls::RuntimeError(
"Could not create link to parameter dataset in master");
}
}
fd.close();
masterfd.close();
} catch (const Exception &error) {
error.printErrorStack();
CloseFile();
throw sls::RuntimeError("Could not link in master hdf5 file");
}
if (!silentMode) {
LOG(logINFO) << "Linked in Master File: " << dataFilename;
}
}
void HDF5MasterFile::CreateMasterFile(const std::string filePath,
const std::string fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr) {
std::ostringstream os;
os << filePath << "/" << fileNamePrefix << "_master"
<< "_" << fileIndex << ".h5";
fileName_ = os.str();
std::lock_guard<std::mutex> lock(*hdf5Lib_);
try {
Exception::dontPrint(); // to handle errors
FileAccPropList flist;
flist.setFcloseDegree(H5F_CLOSE_STRONG);
fd_ = nullptr;
if (!(overWriteEnable))
fd_ = new H5File(fileName_.c_str(), H5F_ACC_EXCL,
FileCreatPropList::DEFAULT, flist);
else
fd_ = new H5File(fileName_.c_str(), H5F_ACC_TRUNC,
FileCreatPropList::DEFAULT, flist);
// attributes - version
double dValue = HDF5_WRITER_VERSION;
DataSpace dataspace_attr = DataSpace(H5S_SCALAR);
Attribute attribute = fd_->createAttribute(
"version", PredType::NATIVE_DOUBLE, dataspace_attr);
attribute.write(PredType::NATIVE_DOUBLE, &dValue);
// Create a group in the file
Group group1(fd_->createGroup("entry"));
Group group2(group1.createGroup("data"));
Group group3(group1.createGroup("instrument"));
Group group4(group3.createGroup("beam"));
Group group5(group3.createGroup("detector"));
Group group6(group1.createGroup("sample"));
// TODO find a way to get complete group link
attrGroupName_ = "/entry/instrument/detector";
attr->WriteMasterHDF5Attributes(fd_, &group5);
fd_->close();
} catch (const Exception &error) {
error.printErrorStack();
CloseFile();
throw sls::RuntimeError(
"Could not create/overwrite master HDF5 handles");
}
if (!silentMode) {
LOG(logINFO) << "Master File: " << fileName_;
}
}
void HDF5MasterFile::UpdateMasterFile(MasterAttributes *attr, bool silentMode) {
std::lock_guard<std::mutex> lock(*hdf5Lib_);
try {
Exception::dontPrint(); // to handle errors
FileAccPropList flist;
flist.setFcloseDegree(H5F_CLOSE_STRONG);
fd_ = new H5File(fileName_.c_str(), H5F_ACC_RDWR,
FileCreatPropList::DEFAULT, flist);
Group group = fd_->openGroup(attrGroupName_.c_str());
attr->WriteFinalHDF5Attributes(fd_, &group);
fd_->close();
} catch (const Exception &error) {
error.printErrorStack();
CloseFile();
throw sls::RuntimeError(
"Could not create/overwrite master HDF5 handles");
}
if (!silentMode) {
LOG(logINFO) << "Updated Master File";
}
}

View File

@ -0,0 +1,31 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#pragma once
#include "File.h"
#include <mutex>
class HDF5MasterFile : private virtual slsDetectorDefs, public File {
public:
HDF5MasterFile(std::mutex *hdf5Lib);
~HDF5MasterFile();
void CloseFile() override;
void LinkDataFile(std::string dataFilename, std::string dataSetname,
const std::vector<std::string> parameterNames,
const bool silentMode) override;
void CreateMasterFile(const std::string filePath,
const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr) override;
void UpdateMasterFile(MasterAttributes *attr, bool silentMode) override;
private:
std::mutex *hdf5Lib_;
H5File *fd_{nullptr};
std::string fileName_;
std::string attrGroupName_;
};

View File

@ -0,0 +1,199 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#include "HDF5VirtualFile.h"
#include "receiver_defs.h"
#include <iomanip>
HDF5VirtualFile::HDF5VirtualFile(std::mutex *hdf5Lib)
: File(HDF5), hdf5Lib_(hdf5Lib) {}
HDF5VirtualFile::~HDF5VirtualFile() { CloseFile(); }
std::array<std::string, 2> HDF5VirtualFile::GetFileAndDatasetName() const {
return std::array<std::string, 2>{fileName_, dataSetName_};
}
void HDF5VirtualFile::CloseFile() {
std::lock_guard<std::mutex> lock(*hdf5Lib_);
try {
Exception::dontPrint(); // to handle errors
if (fd_) {
fd_->close();
delete fd_;
fd_ = nullptr;
}
} catch (const Exception &error) {
LOG(logERROR) << "Could not close virtual HDF5 handles of index";
error.printErrorStack();
}
}
void HDF5VirtualFile::CreateVirtualFile(
const std::string filePath, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const bool silentMode,
const int modulePos, const int numUnitsPerReadout,
const uint32_t maxFramesPerFile, const uint64_t numImages,
const uint32_t nPixelsX, const uint32_t nPixelsY,
const uint32_t dynamicRange, const uint64_t numImagesCaught,
const int numModX, const int numModY, const DataType dataType,
const std::vector<std::string> parameterNames,
const std::vector<DataType> parameterDataTypes) {
// virtual file name
std::ostringstream osfn;
osfn << filePath << "/" << fileNamePrefix << "_virtual"
<< "_" << fileIndex << ".h5";
fileName_ = osfn.str();
unsigned int paraSize = parameterNames.size();
uint64_t numModZ = numModX;
uint32_t nDimy = nPixelsY;
uint32_t nDimz = ((dynamicRange == 4) ? (nPixelsX / 2) : nPixelsX);
std::lock_guard<std::mutex> lock(*hdf5Lib_);
try {
Exception::dontPrint(); // to handle errors
// file
FileAccPropList fapl;
fapl.setFcloseDegree(H5F_CLOSE_STRONG);
fd_ = nullptr;
if (!overWriteEnable)
fd_ = new H5File(fileName_.c_str(), H5F_ACC_EXCL,
FileCreatPropList::DEFAULT, fapl);
else
fd_ = new H5File(fileName_.c_str(), H5F_ACC_TRUNC,
FileCreatPropList::DEFAULT, fapl);
// attributes - version
double dValue = HDF5_WRITER_VERSION;
DataSpace dataspace_attr = DataSpace(H5S_SCALAR);
Attribute attribute = fd_->createAttribute(
"version", PredType::NATIVE_DOUBLE, dataspace_attr);
attribute.write(PredType::NATIVE_DOUBLE, &dValue);
// virtual data dataspace
hsize_t vdsDims[3] = {numImagesCaught, numModY * nDimy,
numModZ * nDimz};
DataSpace vdsDataSpace(3, vdsDims, nullptr);
// virtual parameter dataspace
hsize_t vdsDimsPara[2] = {numImagesCaught,
(unsigned int)numModY * numModZ};
DataSpace vdsDataSpacePara(2, vdsDimsPara, nullptr);
// property list (fill value and datatype)
int fill_value = -1;
DSetCreatPropList plist;
plist.setFillValue(dataType, &fill_value);
// property list for parameters (datatype)
std::vector<DSetCreatPropList> plistPara(paraSize);
// hyperslab
int numMajorHyperslab = numImagesCaught / maxFramesPerFile;
if (numImagesCaught % maxFramesPerFile)
++numMajorHyperslab;
uint64_t framesSaved = 0;
// loop through files
for (int hyperSlab = 0; hyperSlab < numMajorHyperslab; ++hyperSlab) {
uint64_t nDimx =
((numImagesCaught - framesSaved) > maxFramesPerFile)
? maxFramesPerFile
: (numImagesCaught - framesSaved);
hsize_t start[3] = {framesSaved, 0, 0};
hsize_t count[3] = {nDimx, nDimy, nDimz};
hsize_t startPara[2] = {framesSaved, 0};
hsize_t countPara[2] = {nDimx, 1};
// loop through readouts
for (unsigned int i = 0; i < numModY * numModZ; ++i) {
// setect data hyperslabs
vdsDataSpace.selectHyperslab(H5S_SELECT_SET, count, start);
// select parameter hyperslabs
vdsDataSpacePara.selectHyperslab(H5S_SELECT_SET, countPara,
startPara);
// source file name
std::ostringstream os;
os << filePath << "/" << fileNamePrefix << "_d"
<< (modulePos * numUnitsPerReadout + i) << "_f" << hyperSlab
<< '_' << fileIndex << ".h5";
std::string srcFileName = os.str();
LOG(logDEBUG1) << srcFileName;
// find relative path
std::string relative_srcFileName = srcFileName;
{
size_t p = srcFileName.rfind('/', srcFileName.length());
if (p != std::string::npos)
relative_srcFileName = (srcFileName.substr(
p + 1, srcFileName.length() - p));
}
// source dataset name
std::ostringstream osfn;
osfn << "/data";
if (numImages > 1)
osfn << "_f" << std::setfill('0') << std::setw(12)
<< hyperSlab;
std::string srcDatasetName = osfn.str();
// source data dataspace
hsize_t srcDims[3] = {nDimx, nDimy, nDimz};
hsize_t srcDimsMax[3] = {H5S_UNLIMITED, nDimy, nDimz};
DataSpace srcDataSpace(3, srcDims, srcDimsMax);
// source parameter dataspace
hsize_t srcDimsPara[1] = {nDimx};
hsize_t srcDimsMaxPara[1] = {H5S_UNLIMITED};
DataSpace srcDataSpacePara(1, srcDimsPara, srcDimsMaxPara);
// mapping of data property list
plist.setVirtual(vdsDataSpace, relative_srcFileName.c_str(),
srcDatasetName.c_str(), srcDataSpace);
// mapping of parameter property list
for (unsigned int p = 0; p < paraSize; ++p) {
plistPara[p].setVirtual(
vdsDataSpacePara, relative_srcFileName.c_str(),
parameterNames[p].c_str(), srcDataSpacePara);
}
// H5Sclose(srcDataspace);
// H5Sclose(srcDataspace_para);
start[2] += nDimz;
if (start[2] >= (numModZ * nDimz)) {
start[2] = 0;
start[1] += nDimy;
}
startPara[1]++;
}
framesSaved += nDimx;
}
// data dataset
dataSetName_ = "data";
DataSet vdsDataSet(fd_->createDataSet(dataSetName_.c_str(), dataType,
vdsDataSpace, plist));
// parameter dataset
for (unsigned int p = 0; p < paraSize; ++p) {
DataSet vdsDataSetPara(fd_->createDataSet(
parameterNames[p].c_str(), parameterDataTypes[p],
vdsDataSpacePara, plistPara[p]));
}
fd_->close();
} catch (const Exception &error) {
error.printErrorStack();
CloseFile();
throw sls::RuntimeError(
"Could not create/overwrite virtual HDF5 handles");
}
if (!silentMode) {
LOG(logINFO) << "Virtual File: " << fileName_;
}
}

View File

@ -0,0 +1,33 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#pragma once
#include "File.h"
#include <mutex>
class HDF5VirtualFile : private virtual slsDetectorDefs, public File {
public:
HDF5VirtualFile(std::mutex *hdf5Lib);
~HDF5VirtualFile();
std::array<std::string, 2> GetFileAndDatasetName() const override;
void CloseFile() override;
void CreateVirtualFile(
const std::string filePath, const std::string fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable,
const bool silentMode, const int modulePos,
const int numUnitsPerReadout, const uint32_t maxFramesPerFile,
const uint64_t numImages, const uint32_t nPixelsX,
const uint32_t nPixelsY, const uint32_t dynamicRange,
const uint64_t numImagesCaught, const int numModX, const int numModY,
const DataType dataType, const std::vector<std::string> parameterNames,
const std::vector<DataType> parameterDataTypes) override;
private:
std::mutex *hdf5Lib_;
H5File *fd_{nullptr};
std::string fileName_;
std::string dataSetName_;
};

View File

@ -240,6 +240,9 @@ void Implementation::setModulePositionId(const int id) {
xy portGeometry = GetPortGeometry(); xy portGeometry = GetPortGeometry();
streamingPort = DEFAULT_ZMQ_RX_PORTNO + modulePos * portGeometry.x; streamingPort = DEFAULT_ZMQ_RX_PORTNO + modulePos * portGeometry.x;
for (const auto &it : dataProcessor)
it->SetupFileWriter(fileWriteEnable, masterFileWriteEnable,
fileFormatType, modulePos, &hdf5Lib);
assert(numModules.y != 0); assert(numModules.y != 0);
for (unsigned int i = 0; i < listener.size(); ++i) { for (unsigned int i = 0; i < listener.size(); ++i) {
uint16_t row = 0, col = 0; uint16_t row = 0, col = 0;
@ -369,7 +372,8 @@ void Implementation::setFileFormat(const fileFormat f) {
throw sls::RuntimeError("Unknown file format"); throw sls::RuntimeError("Unknown file format");
} }
for (const auto &it : dataProcessor) for (const auto &it : dataProcessor)
it->SetupFileWriter(fileWriteEnable, fileFormatType, &hdf5LibMutex); it->SetupFileWriter(fileWriteEnable, masterFileWriteEnable,
fileFormatType, modulePos, &hdf5Lib);
} }
LOG(logINFO) << "File Format: " << sls::ToString(fileFormatType); LOG(logINFO) << "File Format: " << sls::ToString(fileFormatType);
@ -405,7 +409,8 @@ void Implementation::setFileWriteEnable(const bool b) {
if (fileWriteEnable != b) { if (fileWriteEnable != b) {
fileWriteEnable = b; fileWriteEnable = b;
for (const auto &it : dataProcessor) for (const auto &it : dataProcessor)
it->SetupFileWriter(fileWriteEnable, fileFormatType, &hdf5LibMutex); it->SetupFileWriter(fileWriteEnable, masterFileWriteEnable,
fileFormatType, modulePos, &hdf5Lib);
} }
LOG(logINFO) << "File Write Enable: " LOG(logINFO) << "File Write Enable: "
<< (fileWriteEnable ? "enabled" : "disabled"); << (fileWriteEnable ? "enabled" : "disabled");
@ -418,6 +423,9 @@ bool Implementation::getMasterFileWriteEnable() const {
void Implementation::setMasterFileWriteEnable(const bool b) { void Implementation::setMasterFileWriteEnable(const bool b) {
if (masterFileWriteEnable != b) { if (masterFileWriteEnable != b) {
masterFileWriteEnable = b; masterFileWriteEnable = b;
for (const auto &it : dataProcessor)
it->SetupFileWriter(fileWriteEnable, masterFileWriteEnable,
fileFormatType, modulePos, &hdf5Lib);
} }
LOG(logINFO) << "Master File Write Enable: " LOG(logINFO) << "Master File Write Enable: "
<< (masterFileWriteEnable ? "enabled" : "disabled"); << (masterFileWriteEnable ? "enabled" : "disabled");
@ -445,51 +453,51 @@ void Implementation::setFramesPerFile(const uint32_t i) {
* ************************************************/ * ************************************************/
slsDetectorDefs::runStatus Implementation::getStatus() const { return status; } slsDetectorDefs::runStatus Implementation::getStatus() const { return status; }
std::vector<int64_t> Implementation::getFramesCaught() const { uint64_t Implementation::getFramesCaught() const {
std::vector<int64_t> numFramesCaught(numUDPInterfaces); uint64_t min = -1;
int index = 0; uint32_t flagsum = 0;
for (const auto &it : listener) {
if (it->GetStartedFlag()) { for (const auto &it : dataProcessor) {
numFramesCaught[index] = it->GetNumCompleteFramesCaught(); flagsum += it->GetStartedFlag();
min = std::min(min, it->GetNumCompleteFramesCaught());
} }
++index; // no data processed
} if (flagsum != dataProcessor.size())
return numFramesCaught; return 0;
return min;
} }
std::vector<int64_t> Implementation::getCurrentFrameIndex() const { uint64_t Implementation::getCurrentFrameIndex() const {
std::vector<int64_t> frameIndex(numUDPInterfaces); uint64_t max = 0;
int index = 0; uint32_t flagsum = 0;
for (const auto &it : listener) { for (const auto &it : listener) {
if (it->GetStartedFlag()) { flagsum += it->GetStartedFlag();
frameIndex[index] = it->GetCurrentFrameIndex(); max = std::max(max, it->GetCurrentFrameIndex());
} }
++index; // no data processed
} if (flagsum != listener.size())
return frameIndex; return 0;
return max;
} }
double Implementation::getProgress() const { double Implementation::getProgress() const {
if (!activated || (!detectorDataStream[0] && !detectorDataStream[1])) { // get minimum of processed frame indices
return 100.00; uint64_t currentFrameIndex = 0;
} uint32_t flagsum = 0;
// if disabled, considering only 1 port
double totalFrames = (double)(numberOfTotalFrames * listener.size());
if (!detectorDataStream[0] || !detectorDataStream[1]) {
totalFrames /= 2;
}
double progress = 0;
int index = 0;
for (const auto &it : listener) { for (const auto &it : listener) {
if (detectorDataStream[index] && it->GetStartedFlag()) { flagsum += it->GetStartedFlag();
progress += (it->GetListenedIndex() + 1) / totalFrames; currentFrameIndex = std::max(currentFrameIndex, it->GetListenedIndex());
} }
++index; // no data processed
if (flagsum != listener.size()) {
currentFrameIndex = -1;
} }
progress *= 100;
return progress; return (100.00 *
((double)(currentFrameIndex + 1) / (double)numberOfTotalFrames));
} }
std::vector<int64_t> Implementation::getNumMissingPackets() const { std::vector<int64_t> Implementation::getNumMissingPackets() const {
@ -576,9 +584,29 @@ void Implementation::stopReceiver() {
std::this_thread::sleep_for(std::chrono::milliseconds(5)); std::this_thread::sleep_for(std::chrono::milliseconds(5));
} }
if (fileWriteEnable && modulePos == 0) { #ifdef HDF5C
// master and virtual file (hdf5) if (fileWriteEnable && fileFormatType == HDF5) {
StartMasterWriter(); if (modulePos == 0) {
// more than 1 file, create virtual file
if (dataProcessor[0]->GetFilesInAcquisition() > 1 ||
(numModules.x * numModules.y) > 1) {
dataProcessor[0]->CreateVirtualFile(
filePath, fileName, fileIndex, overwriteEnable, silentMode,
modulePos, numUDPInterfaces, framesPerFile,
numberOfTotalFrames, dynamicRange, numModules.x,
numModules.y, &hdf5Lib);
}
// link file in master
dataProcessor[0]->LinkDataInMasterFile(silentMode);
}
}
#endif
if (fileWriteEnable && masterFileWriteEnable && modulePos == 0) {
try {
dataProcessor[0]->UpdateMasterFile(silentMode);
} catch (...) {
; // ignore it and just print it
}
} }
// wait for the processes (dataStreamer) to be done // wait for the processes (dataStreamer) to be done
@ -599,7 +627,7 @@ void Implementation::stopReceiver() {
// print summary // print summary
uint64_t tot = 0; uint64_t tot = 0;
for (int i = 0; i < numUDPInterfaces; i++) { for (int i = 0; i < numUDPInterfaces; i++) {
int nf = listener[i]->GetNumCompleteFramesCaught(); int nf = dataProcessor[i]->GetNumCompleteFramesCaught();
tot += nf; tot += nf;
std::string mpMessage = std::to_string(mp[i]); std::string mpMessage = std::to_string(mp[i]);
if (mp[i] < 0) { if (mp[i] < 0) {
@ -725,12 +753,100 @@ void Implementation::CreateUDPSockets() {
} }
void Implementation::SetupWriter() { void Implementation::SetupWriter() {
// master file
std::unique_ptr<MasterAttributes> masterAttributes;
if (masterFileWriteEnable && modulePos == 0) {
switch (detType) {
case GOTTHARD:
masterAttributes = sls::make_unique<GotthardMasterAttributes>();
break;
case JUNGFRAU:
masterAttributes = sls::make_unique<JungfrauMasterAttributes>();
break;
case EIGER:
masterAttributes = sls::make_unique<EigerMasterAttributes>();
break;
case MYTHEN3:
masterAttributes = sls::make_unique<Mythen3MasterAttributes>();
break;
case GOTTHARD2:
masterAttributes = sls::make_unique<Gotthard2MasterAttributes>();
break;
case MOENCH:
masterAttributes = sls::make_unique<MoenchMasterAttributes>();
break;
case CHIPTESTBOARD:
masterAttributes = sls::make_unique<CtbMasterAttributes>();
break;
default:
throw sls::RuntimeError(
"Unknown detector type to set up master file attributes");
}
masterAttributes->detType = detType;
masterAttributes->timingMode = timingMode;
xy nm{numModules.x, numModules.y};
if (quadEnable) {
nm.x = 1;
nm.y = 2;
}
masterAttributes->geometry = xy(nm.x, nm.y);
masterAttributes->imageSize = generalData->imageSize;
masterAttributes->nPixels =
xy(generalData->nPixelsX, generalData->nPixelsY);
masterAttributes->maxFramesPerFile = framesPerFile;
masterAttributes->frameDiscardMode = frameDiscardMode;
masterAttributes->framePadding = framePadding;
masterAttributes->scanParams = scanParams;
masterAttributes->totalFrames = numberOfTotalFrames;
masterAttributes->exptime = acquisitionTime;
masterAttributes->period = acquisitionPeriod;
masterAttributes->burstMode = burstMode;
masterAttributes->numUDPInterfaces = numUDPInterfaces;
masterAttributes->dynamicRange = dynamicRange;
masterAttributes->tenGiga = tengigaEnable;
masterAttributes->thresholdEnergyeV = thresholdEnergyeV;
masterAttributes->thresholdAllEnergyeV = thresholdAllEnergyeV;
masterAttributes->subExptime = subExpTime;
masterAttributes->subPeriod = subPeriod;
masterAttributes->quad = quadEnable;
masterAttributes->readNRows = readNRows;
masterAttributes->ratecorr = rateCorrections;
masterAttributes->adcmask =
tengigaEnable ? adcEnableMaskTenGiga : adcEnableMaskOneGiga;
masterAttributes->analog =
(readoutType == ANALOG_ONLY || readoutType == ANALOG_AND_DIGITAL)
? 1
: 0;
masterAttributes->analogSamples = numberOfAnalogSamples;
masterAttributes->digital =
(readoutType == DIGITAL_ONLY || readoutType == ANALOG_AND_DIGITAL)
? 1
: 0;
masterAttributes->digitalSamples = numberOfDigitalSamples;
masterAttributes->dbitoffset = ctbDbitOffset;
masterAttributes->dbitlist = 0;
for (auto &i : ctbDbitList) {
masterAttributes->dbitlist |= (1 << i);
}
masterAttributes->roi = roi;
masterAttributes->counterMask = counterMask;
masterAttributes->exptime1 = acquisitionTime1;
masterAttributes->exptime2 = acquisitionTime2;
masterAttributes->exptime3 = acquisitionTime3;
masterAttributes->gateDelay1 = gateDelay1;
masterAttributes->gateDelay2 = gateDelay2;
masterAttributes->gateDelay3 = gateDelay3;
masterAttributes->gates = numberOfGates;
masterAttributes->additionalJsonHeader = additionalJsonHeader;
}
try { try {
for (unsigned int i = 0; i < dataProcessor.size(); ++i) { for (unsigned int i = 0; i < dataProcessor.size(); ++i) {
dataProcessor[i]->CreateFirstFiles( dataProcessor[i]->CreateFirstFiles(
filePath, fileName, fileIndex, overwriteEnable, silentMode, masterAttributes.get(), filePath, fileName, fileIndex,
modulePos, numUDPInterfaces, udpPortNum[i], framesPerFile, overwriteEnable, silentMode, modulePos, numUDPInterfaces,
numberOfTotalFrames, dynamicRange, detectorDataStream[i]); udpPortNum[i], framesPerFile, numberOfTotalFrames, dynamicRange,
detectorDataStream[i]);
} }
} catch (const sls::RuntimeError &e) { } catch (const sls::RuntimeError &e) {
shutDownUDPSockets(); shutDownUDPSockets();
@ -740,100 +856,6 @@ void Implementation::SetupWriter() {
} }
} }
void Implementation::StartMasterWriter() {
try {
std::string masterFileName;
// master file
if (masterFileWriteEnable) {
MasterAttributes masterAttributes;
masterAttributes.detType = detType;
masterAttributes.timingMode = timingMode;
xy nm{numModules.x, numModules.y};
if (quadEnable) {
nm.x = 1;
nm.y = 2;
}
masterAttributes.geometry = xy(nm.x, nm.y);
masterAttributes.imageSize = generalData->imageSize;
masterAttributes.nPixels =
xy(generalData->nPixelsX, generalData->nPixelsY);
masterAttributes.maxFramesPerFile = framesPerFile;
masterAttributes.frameDiscardMode = frameDiscardMode;
masterAttributes.framePadding = framePadding;
masterAttributes.scanParams = scanParams;
masterAttributes.totalFrames = numberOfTotalFrames;
masterAttributes.exptime = acquisitionTime;
masterAttributes.period = acquisitionPeriod;
masterAttributes.burstMode = burstMode;
masterAttributes.numUDPInterfaces = numUDPInterfaces;
masterAttributes.dynamicRange = dynamicRange;
masterAttributes.tenGiga = tengigaEnable;
masterAttributes.thresholdEnergyeV = thresholdEnergyeV;
masterAttributes.thresholdAllEnergyeV = thresholdAllEnergyeV;
masterAttributes.subExptime = subExpTime;
masterAttributes.subPeriod = subPeriod;
masterAttributes.quad = quadEnable;
masterAttributes.readNRows = readNRows;
masterAttributes.ratecorr = rateCorrections;
masterAttributes.adcmask =
tengigaEnable ? adcEnableMaskTenGiga : adcEnableMaskOneGiga;
masterAttributes.analog = (readoutType == ANALOG_ONLY ||
readoutType == ANALOG_AND_DIGITAL)
? 1
: 0;
masterAttributes.analogSamples = numberOfAnalogSamples;
masterAttributes.digital = (readoutType == DIGITAL_ONLY ||
readoutType == ANALOG_AND_DIGITAL)
? 1
: 0;
masterAttributes.digitalSamples = numberOfDigitalSamples;
masterAttributes.dbitoffset = ctbDbitOffset;
masterAttributes.dbitlist = 0;
for (auto &i : ctbDbitList) {
masterAttributes.dbitlist |= (1 << i);
}
masterAttributes.roi = roi;
masterAttributes.counterMask = counterMask;
masterAttributes.exptimeArray[0] = acquisitionTime1;
masterAttributes.exptimeArray[1] = acquisitionTime2;
masterAttributes.exptimeArray[2] = acquisitionTime3;
masterAttributes.gateDelayArray[0] = gateDelay1;
masterAttributes.gateDelayArray[1] = gateDelay2;
masterAttributes.gateDelayArray[2] = gateDelay3;
masterAttributes.gates = numberOfGates;
masterAttributes.additionalJsonHeader = additionalJsonHeader;
// create master file
masterFileName = dataProcessor[0]->CreateMasterFile(
filePath, fileName, fileIndex, overwriteEnable, silentMode,
fileFormatType, &masterAttributes, &hdf5LibMutex);
}
#ifdef HDF5C
if (fileFormatType == HDF5) {
std::array<std::string, 2> virtualFileAndDatasetNames;
// create virtual hdf5 file (if multiple files)
if (dataProcessor[0]->GetFilesInAcquisition() > 1 ||
(numModules.x * numModules.y) > 1) {
virtualFileAndDatasetNames =
dataProcessor[0]->CreateVirtualFile(
filePath, fileName, fileIndex, overwriteEnable,
silentMode, modulePos, numUDPInterfaces, framesPerFile,
numberOfTotalFrames, numModules.x, numModules.y,
dynamicRange, &hdf5LibMutex);
}
// link file in master
if (masterFileWriteEnable) {
dataProcessor[0]->LinkFileInMaster(
masterFileName, virtualFileAndDatasetNames[0],
virtualFileAndDatasetNames[1], silentMode, &hdf5LibMutex);
}
}
#endif
} catch (...) {
; // ignore it and just print it
}
}
void Implementation::StartRunning() { void Implementation::StartRunning() {
// set running mask and post semaphore to start the inner loop in execution // set running mask and post semaphore to start the inner loop in execution

View File

@ -84,8 +84,8 @@ class Implementation : private virtual slsDetectorDefs {
* * * *
* ************************************************/ * ************************************************/
runStatus getStatus() const; runStatus getStatus() const;
std::vector<int64_t> getFramesCaught() const; uint64_t getFramesCaught() const;
std::vector<int64_t> getCurrentFrameIndex() const; uint64_t getCurrentFrameIndex() const;
double getProgress() const; double getProgress() const;
std::vector<int64_t> getNumMissingPackets() const; std::vector<int64_t> getNumMissingPackets() const;
void setScan(slsDetectorDefs::scanParameters s); void setScan(slsDetectorDefs::scanParameters s);
@ -274,7 +274,6 @@ class Implementation : private virtual slsDetectorDefs {
void ResetParametersforNewAcquisition(); void ResetParametersforNewAcquisition();
void CreateUDPSockets(); void CreateUDPSockets();
void SetupWriter(); void SetupWriter();
void StartMasterWriter();
void StartRunning(); void StartRunning();
/************************************************** /**************************************************
@ -387,6 +386,5 @@ class Implementation : private virtual slsDetectorDefs {
std::vector<std::unique_ptr<Fifo>> fifo; std::vector<std::unique_ptr<Fifo>> fifo;
Arping arping; Arping arping;
// mutex shared across all hdf5 virtual, master and data files std::mutex hdf5Lib;
std::mutex hdf5LibMutex;
}; };

View File

@ -36,22 +36,12 @@ Listener::~Listener() = default;
uint64_t Listener::GetPacketsCaught() const { return numPacketsCaught; } uint64_t Listener::GetPacketsCaught() const { return numPacketsCaught; }
uint64_t Listener::GetNumCompleteFramesCaught() const {
return numCompleteFramesCaught;
}
uint64_t Listener::GetLastFrameIndexCaught() const { uint64_t Listener::GetLastFrameIndexCaught() const {
return lastCaughtFrameIndex; return lastCaughtFrameIndex;
} }
int64_t Listener::GetNumMissingPacket(bool stoppedFlag, int64_t Listener::GetNumMissingPacket(bool stoppedFlag,
uint64_t numPackets) const { uint64_t numPackets) const {
if (!activated) {
return 0;
}
if (!(*detectorDataStream)) {
return 0;
}
if (!stoppedFlag) { if (!stoppedFlag) {
return (numPackets - numPacketsCaught); return (numPackets - numPacketsCaught);
} }
@ -63,11 +53,11 @@ int64_t Listener::GetNumMissingPacket(bool stoppedFlag,
numPacketsCaught; numPacketsCaught;
} }
bool Listener::GetStartedFlag() const { return startedFlag; } bool Listener::GetStartedFlag() { return startedFlag; }
uint64_t Listener::GetCurrentFrameIndex() const { return lastCaughtFrameIndex; } uint64_t Listener::GetCurrentFrameIndex() { return lastCaughtFrameIndex; }
uint64_t Listener::GetListenedIndex() const { uint64_t Listener::GetListenedIndex() {
return lastCaughtFrameIndex - firstIndex; return lastCaughtFrameIndex - firstIndex;
} }
@ -77,7 +67,6 @@ void Listener::ResetParametersforNewAcquisition() {
StopRunning(); StopRunning();
startedFlag = false; startedFlag = false;
numPacketsCaught = 0; numPacketsCaught = 0;
numCompleteFramesCaught = 0;
firstIndex = 0; firstIndex = 0;
currentFrameIndex = 0; currentFrameIndex = 0;
lastCaughtFrameIndex = 0; lastCaughtFrameIndex = 0;
@ -618,9 +607,6 @@ uint32_t Listener::ListenToAnImage(char *buf) {
// complete image // complete image
new_header->detHeader.packetNumber = numpackets; // number of packets caught new_header->detHeader.packetNumber = numpackets; // number of packets caught
new_header->detHeader.frameNumber = currentFrameIndex; new_header->detHeader.frameNumber = currentFrameIndex;
if (numpackets == pperFrame) {
++numCompleteFramesCaught;
}
++currentFrameIndex; ++currentFrameIndex;
return imageSize; return imageSize;
} }

View File

@ -51,19 +51,53 @@ class Listener : private virtual slsDetectorDefs, public ThreadObject {
*/ */
~Listener(); ~Listener();
/**
* Get Packets caught
* @return Packets caught
*/
uint64_t GetPacketsCaught() const; uint64_t GetPacketsCaught() const;
uint64_t GetNumCompleteFramesCaught() const;
uint64_t GetLastFrameIndexCaught() const;
/** negative values in case of extra packets */
int64_t GetNumMissingPacket(bool stoppedFlag, uint64_t numPackets) const;
bool GetStartedFlag() const;
uint64_t GetCurrentFrameIndex() const;
uint64_t GetListenedIndex() const;
/**
* Get Last Frame index caught
* @return last frame index caught
*/
uint64_t GetLastFrameIndexCaught() const;
/** Get number of missing packets, returns negative values in case to extra
* packet */
int64_t GetNumMissingPacket(bool stoppedFlag, uint64_t numPackets) const;
bool GetStartedFlag();
uint64_t GetCurrentFrameIndex();
/** (-1 if no frames have been caught) */
uint64_t GetListenedIndex();
/**
* Set Fifo pointer to the one given
* @param f address of Fifo pointer
*/
void SetFifo(Fifo *f); void SetFifo(Fifo *f);
/**
* Reset parameters for new acquisition
*/
void ResetParametersforNewAcquisition(); void ResetParametersforNewAcquisition();
/**
* Set GeneralData pointer to the one given
* @param g address of GeneralData (Detector Data) pointer
*/
void SetGeneralData(GeneralData *g); void SetGeneralData(GeneralData *g);
/**
* Creates UDP Sockets
*/
void CreateUDPSockets(); void CreateUDPSockets();
/**
* Shuts down and deletes UDP Sockets
*/
void ShutDownUDPSocket(); void ShutDownUDPSocket();
/** /**
@ -82,6 +116,10 @@ class Listener : private virtual slsDetectorDefs, public ThreadObject {
void SetHardCodedPosition(uint16_t r, uint16_t c); void SetHardCodedPosition(uint16_t r, uint16_t c);
private: private:
/**
* Record First Acquisition Index
* @param fnum frame index to record
*/
void RecordFirstIndex(uint64_t fnum); void RecordFirstIndex(uint64_t fnum);
/** /**
@ -108,25 +146,55 @@ class Listener : private virtual slsDetectorDefs, public ThreadObject {
*/ */
uint32_t ListenToAnImage(char *buf); uint32_t ListenToAnImage(char *buf);
/**
* Print Fifo Statistics
*/
void PrintFifoStatistics(); void PrintFifoStatistics();
/** type of thread */
static const std::string TypeName; static const std::string TypeName;
/** GeneralData (Detector Data) object */
GeneralData *generalData{nullptr}; GeneralData *generalData{nullptr};
/** Fifo structure */
Fifo *fifo; Fifo *fifo;
// individual members // individual members
/** Detector Type */
detectorType myDetectorType; detectorType myDetectorType;
/** Receiver Status */
std::atomic<runStatus> *status; std::atomic<runStatus> *status;
/** UDP Socket - Detector to Receiver */
std::unique_ptr<sls::UdpRxSocket> udpSocket{nullptr}; std::unique_ptr<sls::UdpRxSocket> udpSocket{nullptr};
/** UDP Port Number */
uint32_t *udpPortNumber; uint32_t *udpPortNumber;
/** ethernet interface */
std::string *eth; std::string *eth;
/** UDP Socket Buffer Size */
int *udpSocketBufferSize; int *udpSocketBufferSize;
/** double due to kernel bookkeeping */
/** actual UDP Socket Buffer Size (double due to kernel bookkeeping) */
int *actualUDPSocketBufferSize; int *actualUDPSocketBufferSize;
/** frames per file */
uint32_t *framesPerFile; uint32_t *framesPerFile;
/** frame discard policy */
frameDiscardPolicy *frameDiscardMode; frameDiscardPolicy *frameDiscardMode;
/** Activated/Deactivated */
bool *activated; bool *activated;
/** detector data stream */
bool *detectorDataStream; bool *detectorDataStream;
/** Silent Mode */
bool *silentMode; bool *silentMode;
/** row hardcoded as 1D or 2d, /** row hardcoded as 1D or 2d,
@ -141,12 +209,15 @@ class Listener : private virtual slsDetectorDefs, public ThreadObject {
// acquisition start // acquisition start
/** Aquisition Started flag */ /** Aquisition Started flag */
std::atomic<bool> startedFlag{false}; std::atomic<bool> startedFlag{false};
/** Frame Number of First Frame */ /** Frame Number of First Frame */
uint64_t firstIndex{0}; uint64_t firstIndex{0};
// for acquisition summary // for acquisition summary
/** Number of complete Packets caught */
std::atomic<uint64_t> numPacketsCaught{0}; std::atomic<uint64_t> numPacketsCaught{0};
std::atomic<uint64_t> numCompleteFramesCaught{0};
/** Last Frame Index caught from udp network */
std::atomic<uint64_t> lastCaughtFrameIndex{0}; std::atomic<uint64_t> lastCaughtFrameIndex{0};
// parameters to acquire image // parameters to acquire image
@ -154,16 +225,25 @@ class Listener : private virtual slsDetectorDefs, public ThreadObject {
* ( always check startedFlag for validity first) * ( always check startedFlag for validity first)
*/ */
uint64_t currentFrameIndex{0}; uint64_t currentFrameIndex{0};
/** True if there is a packet carry over from previous Image */ /** True if there is a packet carry over from previous Image */
bool carryOverFlag{false}; bool carryOverFlag{false};
/** Carry over packet buffer */
std::unique_ptr<char[]> carryOverPacket; std::unique_ptr<char[]> carryOverPacket;
/** Listening buffer for one packet - might be removed when we can peek and /** Listening buffer for one packet - might be removed when we can peek and
* eiger fnum is in header */ * eiger fnum is in header */
std::unique_ptr<char[]> listeningPacket; std::unique_ptr<char[]> listeningPacket;
/** if the udp socket is connected */
std::atomic<bool> udpSocketAlive{false}; std::atomic<bool> udpSocketAlive{false};
// for print progress during acquisition*/ // for print progress during acquisition
/** number of packets for statistic */
uint32_t numPacketsStatistic{0}; uint32_t numPacketsStatistic{0};
/** number of images for statistic */
uint32_t numFramesStatistic{0}; uint32_t numFramesStatistic{0};
/** /**

File diff suppressed because it is too large Load Diff

View File

@ -7,9 +7,6 @@
#include "sls/logger.h" #include "sls/logger.h"
#include "sls/sls_detector_defs.h" #include "sls/sls_detector_defs.h"
#include <rapidjson/stringbuffer.h>
#include <rapidjson/prettywriter.h>
#ifdef HDF5C #ifdef HDF5C
#include "H5Cpp.h" #include "H5Cpp.h"
#ifndef H5_NO_NAMESPACE #ifndef H5_NO_NAMESPACE
@ -56,92 +53,94 @@ class MasterAttributes {
uint64_t dbitlist{0}; uint64_t dbitlist{0};
slsDetectorDefs::ROI roi{}; slsDetectorDefs::ROI roi{};
uint32_t counterMask{0}; uint32_t counterMask{0};
std::array<ns, 3> exptimeArray{}; ns exptime1{0};
std::array<ns, 3> gateDelayArray{}; ns exptime2{0};
ns exptime3{0};
ns gateDelay1{0};
ns gateDelay2{0};
ns gateDelay3{0};
uint32_t gates; uint32_t gates;
std::map<std::string, std::string> additionalJsonHeader; std::map<std::string, std::string> additionalJsonHeader;
// Final Attributes (after acquisition)
uint64_t framesInFile{0}; uint64_t framesInFile{0};
MasterAttributes() = default; MasterAttributes() = default;
~MasterAttributes() = default; virtual ~MasterAttributes() = default;
virtual void WriteMasterBinaryAttributes(FILE *fd);
void GetBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); std::string GetBinaryMasterAttributes();
void WriteBinaryAttributes(FILE *fd, std::string message);
void WriteFinalBinaryAttributes(FILE *fd);
#ifdef HDF5C #ifdef HDF5C
virtual void WriteMasterHDF5Attributes(H5File *fd, Group *group);
void WriteHDF5Attributes(H5File *fd, Group *group); void WriteHDF5Attributes(H5File *fd, Group *group);
#endif
void
GetCommonBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w);
void
GetFinalBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w);
#ifdef HDF5C
void WriteCommonHDF5Attributes(H5File *fd, Group *group);
void WriteFinalHDF5Attributes(H5File *fd, Group *group); void WriteFinalHDF5Attributes(H5File *fd, Group *group);
void WriteHDF5Exptime(H5File *fd, Group *group); void WriteHDF5Exptime(H5File *fd, Group *group);
void WriteHDF5Period(H5File *fd, Group *group); void WriteHDF5Period(H5File *fd, Group *group);
void WriteHDF5DynamicRange(H5File *fd, Group *group); void WriteHDF5DynamicRange(H5File *fd, Group *group);
void WriteHDF5TenGiga(H5File *fd, Group *group); void WriteHDF5TenGiga(H5File *fd, Group *group);
void WriteHDF5ROI(H5File *fd, Group *group); #endif
void WriteHDF5NumUDPInterfaces(H5File *fd, Group *group); };
void WriteHDF5ReadNRows(H5File *fd, Group *group);
void WriteHDF5ThresholdEnergy(H5File *fd, Group *group); class GotthardMasterAttributes : public MasterAttributes {
void WriteHDF5ThresholdEnergies(H5File *fd, Group *group); public:
void WriteHDF5SubExpTime(H5File *fd, Group *group); GotthardMasterAttributes() = default;
void WriteHDF5SubPeriod(H5File *fd, Group *group); void WriteMasterBinaryAttributes(FILE *fd) override;
void WriteHDF5SubQuad(H5File *fd, Group *group); #ifdef HDF5C
void WriteHDF5RateCorrections(H5File *fd, Group *group); void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
void WriteHDF5CounterMask(H5File *fd, Group *group); #endif
void WriteHDF5ExptimeArray(H5File *fd, Group *group); };
void WriteHDF5GateDelayArray(H5File *fd, Group *group);
void WriteHDF5Gates(H5File *fd, Group *group); class JungfrauMasterAttributes : public MasterAttributes {
void WriteHDF5BurstMode(H5File *fd, Group *group); public:
void WriteHDF5AdcMask(H5File *fd, Group *group); JungfrauMasterAttributes() = default;
void WriteHDF5AnalogFlag(H5File *fd, Group *group); void WriteMasterBinaryAttributes(FILE *fd) override;
void WriteHDF5AnalogSamples(H5File *fd, Group *group); #ifdef HDF5C
void WriteHDF5DigitalFlag(H5File *fd, Group *group); void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
void WriteHDF5DigitalSamples(H5File *fd, Group *group); #endif
void WriteHDF5DbitOffset(H5File *fd, Group *group); };
void WriteHDF5DbitList(H5File *fd, Group *group);
#endif class EigerMasterAttributes : public MasterAttributes {
public:
void EigerMasterAttributes() = default;
GetGotthardBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); void WriteMasterBinaryAttributes(FILE *fd) override;
#ifdef HDF5C #ifdef HDF5C
void WriteGotthardHDF5Attributes(H5File *fd, Group *group); void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
#endif #endif
};
void
GetJungfrauBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); class Mythen3MasterAttributes : public MasterAttributes {
#ifdef HDF5C public:
void WriteJungfrauHDF5Attributes(H5File *fd, Group *group); Mythen3MasterAttributes() = default;
#endif void WriteMasterBinaryAttributes(FILE *fd) override;
#ifdef HDF5C
void void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
GetEigerBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); #endif
#ifdef HDF5C };
void WriteEigerHDF5Attributes(H5File *fd, Group *group);
#endif class Gotthard2MasterAttributes : public MasterAttributes {
public:
void Gotthard2MasterAttributes() = default;
GetMythen3BinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); void WriteMasterBinaryAttributes(FILE *fd) override;
#ifdef HDF5C #ifdef HDF5C
void WriteMythen3HDF5Attributes(H5File *fd, Group *group); void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
#endif #endif
};
void
GetGotthard2BinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); class MoenchMasterAttributes : public MasterAttributes {
#ifdef HDF5C public:
void WriteGotthard2HDF5Attributes(H5File *fd, Group *group); MoenchMasterAttributes() = default;
#endif void WriteMasterBinaryAttributes(FILE *fd) override;
#ifdef HDF5C
void void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
GetMoenchBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); #endif
#ifdef HDF5C };
void WriteMoenchHDF5Attributes(H5File *fd, Group *group);
#endif class CtbMasterAttributes : public MasterAttributes {
public:
void GetCtbBinaryAttributes(rapidjson::PrettyWriter<rapidjson::StringBuffer> *w); CtbMasterAttributes() = default;
#ifdef HDF5C void WriteMasterBinaryAttributes(FILE *fd) override;
void WriteCtbHDF5Attributes(H5File *fd, Group *group); #ifdef HDF5C
void WriteMasterHDF5Attributes(H5File *fd, Group *group) override;
#endif #endif
}; };

View File

@ -1,351 +0,0 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#include "MasterFileUtility.h"
#include "sls/container_utils.h"
#include <iomanip>
namespace masterFileUtility {
std::string CreateMasterBinaryFile(const std::string &filePath,
const std::string &fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr) {
std::ostringstream os;
os << filePath << "/" << fileNamePrefix << "_master"
<< "_" << fileIndex << ".json";
std::string fileName = os.str();
std::string mode = "w";
if (!overWriteEnable)
mode = "wx";
FILE *fd = fopen(fileName.c_str(), mode.c_str());
if(!fd) {
throw sls::RuntimeError("Could not create/overwrite binary master file " +
fileName);
}
rapidjson::StringBuffer s;
rapidjson::PrettyWriter<rapidjson::StringBuffer> writer(s);
attr->GetBinaryAttributes(&writer);
if (fwrite(s.GetString(), 1, strlen(s.GetString()), fd) !=
strlen(s.GetString())) {
throw sls::RuntimeError(
"Master binary file incorrect number of bytes written to file");
}
if (fd) {
fclose(fd);
}
if (!silentMode) {
LOG(logINFO) << "Master File: " << fileName;
}
return fileName;
}
#ifdef HDF5C
void LinkHDF5FileInMaster(const std::string &masterFileName,
const std::string &dataFilename,
const std::string &dataSetname,
const std::vector<std::string> parameterNames,
const bool silentMode, std::mutex *hdf5LibMutex) {
std::lock_guard<std::mutex> lock(*hdf5LibMutex);
std::unique_ptr<H5File> fd{nullptr};
try {
Exception::dontPrint(); // to handle errors
FileAccPropList flist;
flist.setFcloseDegree(H5F_CLOSE_STRONG);
// open master file
H5File masterfd(masterFileName.c_str(), H5F_ACC_RDWR,
FileCreatPropList::DEFAULT, flist);
// open data file
fd = sls::make_unique<H5File>(dataFilename.c_str(), H5F_ACC_RDONLY,
FileCreatPropList::DEFAULT, flist);
// create link for data dataset
DataSet dset = fd->openDataSet(dataSetname.c_str());
std::string linkname = std::string("/entry/data/") + dataSetname;
if (H5Lcreate_external(dataFilename.c_str(), dataSetname.c_str(),
masterfd.getLocId(), linkname.c_str(),
H5P_DEFAULT, H5P_DEFAULT) < 0) {
throw sls::RuntimeError(
"Could not create link to data dataset in master");
}
// create link for parameter datasets
for (unsigned int i = 0; i < parameterNames.size(); ++i) {
DataSet pDset = fd->openDataSet(parameterNames[i].c_str());
linkname = std::string("/entry/data/") + parameterNames[i];
if (H5Lcreate_external(dataFilename.c_str(),
parameterNames[i].c_str(),
masterfd.getLocId(), linkname.c_str(),
H5P_DEFAULT, H5P_DEFAULT) < 0) {
throw sls::RuntimeError(
"Could not create link to parameter dataset in master");
}
}
fd->close();
masterfd.close();
} catch (const Exception &error) {
error.printErrorStack();
if (fd != nullptr)
fd->close();
throw sls::RuntimeError("Could not link in master hdf5 file");
}
if (!silentMode) {
LOG(logINFO) << "Linked in Master File: " << dataFilename;
}
}
std::string CreateMasterHDF5File(const std::string &filePath,
const std::string &fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode, MasterAttributes *attr,
std::mutex *hdf5LibMutex) {
std::ostringstream os;
os << filePath << "/" << fileNamePrefix << "_master"
<< "_" << fileIndex << ".h5";
std::string fileName = os.str();
std::lock_guard<std::mutex> lock(*hdf5LibMutex);
std::unique_ptr<H5File> fd{nullptr};
try {
Exception::dontPrint(); // to handle errors
FileAccPropList flist;
flist.setFcloseDegree(H5F_CLOSE_STRONG);
unsigned int createFlags = H5F_ACC_EXCL;
if (overWriteEnable) {
createFlags = H5F_ACC_TRUNC;
}
fd = sls::make_unique<H5File>(fileName.c_str(), createFlags,
FileCreatPropList::DEFAULT, flist);
// attributes - version
double dValue = HDF5_WRITER_VERSION;
DataSpace dataspace_attr = DataSpace(H5S_SCALAR);
Attribute attribute = fd->createAttribute(
"version", PredType::NATIVE_DOUBLE, dataspace_attr);
attribute.write(PredType::NATIVE_DOUBLE, &dValue);
// Create a group in the file
Group group1(fd->createGroup("entry"));
Group group2(group1.createGroup("data"));
Group group3(group1.createGroup("instrument"));
Group group4(group3.createGroup("beam"));
Group group5(group3.createGroup("detector"));
Group group6(group1.createGroup("sample"));
attr->WriteHDF5Attributes(fd.get(), &group5);
fd->close();
} catch (const Exception &error) {
error.printErrorStack();
if (fd != nullptr)
fd->close();
throw sls::RuntimeError(
"Could not create/overwrite master HDF5 handles");
}
if (!silentMode) {
LOG(logINFO) << "Master File: " << fileName;
}
return fileName;
}
std::array<std::string, 2> CreateVirtualHDF5File(
const std::string &filePath, const std::string &fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const bool silentMode,
const int modulePos, const int numUnitsPerReadout,
const uint32_t maxFramesPerFile, const uint64_t numImages,
const uint32_t nPixelsX, const uint32_t nPixelsY,
const uint32_t dynamicRange, const uint64_t numImagesCaught,
const int numModX, const int numModY, const DataType dataType,
const std::vector<std::string> parameterNames,
const std::vector<DataType> parameterDataTypes, std::mutex *hdf5LibMutex,
bool gotthard25um) {
// virtual file name
std::ostringstream osfn;
osfn << filePath << "/" << fileNamePrefix << "_virtual"
<< "_" << fileIndex << ".h5";
std::string fileName = osfn.str();
std::string dataSetName = "data";
unsigned int paraSize = parameterNames.size();
uint64_t numModZ = numModX;
uint32_t nDimy = nPixelsY;
uint32_t nDimz = ((dynamicRange == 4) ? (nPixelsX / 2) : nPixelsX);
std::lock_guard<std::mutex> lock(*hdf5LibMutex);
std::unique_ptr<H5File> fd{nullptr};
try {
Exception::dontPrint(); // to handle errors
// file
FileAccPropList fapl;
fapl.setFcloseDegree(H5F_CLOSE_STRONG);
if (!overWriteEnable)
fd = sls::make_unique<H5File>(fileName.c_str(), H5F_ACC_EXCL,
FileCreatPropList::DEFAULT, fapl);
else
fd = sls::make_unique<H5File>(fileName.c_str(), H5F_ACC_TRUNC,
FileCreatPropList::DEFAULT, fapl);
// attributes - version
double dValue = HDF5_WRITER_VERSION;
DataSpace dataspace_attr = DataSpace(H5S_SCALAR);
Attribute attribute = fd->createAttribute(
"version", PredType::NATIVE_DOUBLE, dataspace_attr);
attribute.write(PredType::NATIVE_DOUBLE, &dValue);
// virtual dataspace
hsize_t vdsDims[3] = {numImagesCaught, numModY * nDimy,
numModZ * nDimz};
DataSpace vdsDataSpace(3, vdsDims, nullptr);
hsize_t vdsDimsPara[2] = {numImagesCaught,
(unsigned int)numModY * numModZ};
DataSpace vdsDataSpacePara(2, vdsDimsPara, nullptr);
// property list (fill value and datatype)
int fill_value = -1;
DSetCreatPropList plist;
plist.setFillValue(dataType, &fill_value);
// property list for parameters (datatype)
std::vector<DSetCreatPropList> plistPara(paraSize);
// hyperslab (files)
int numFiles = numImagesCaught / maxFramesPerFile;
if (numImagesCaught % maxFramesPerFile)
++numFiles;
uint64_t framesSaved = 0;
for (int iFile = 0; iFile < numFiles; ++iFile) {
uint64_t nDimx =
((numImagesCaught - framesSaved) > maxFramesPerFile)
? maxFramesPerFile
: (numImagesCaught - framesSaved);
hsize_t startLocation[3] = {framesSaved, 0, 0};
hsize_t strideBetweenBlocks[3] = {1, 1, 1};
hsize_t numBlocks[3] = {nDimx, nDimy, nDimz};
hsize_t blockSize[3] = {1, 1, 1};
hsize_t startLocationPara[2] = {framesSaved, 0};
hsize_t strideBetweenBlocksPara[3] = {1, 1};
hsize_t numBlocksPara[2] = {1, 1};
hsize_t blockSizePara[3] = {nDimx, 1};
// interleaving for g2
if (gotthard25um) {
strideBetweenBlocks[2] = 2;
}
for (unsigned int iReadout = 0; iReadout < numModY * numModZ;
++iReadout) {
// interleaving for g2 (startLocation is 0 and 1)
if (gotthard25um) {
startLocation[2] = iReadout;
}
vdsDataSpace.selectHyperslab(H5S_SELECT_SET, numBlocks,
startLocation, strideBetweenBlocks,
blockSize);
vdsDataSpacePara.selectHyperslab(
H5S_SELECT_SET, numBlocksPara, startLocationPara,
strideBetweenBlocksPara, blockSizePara);
// source file name
std::ostringstream os;
os << filePath << "/" << fileNamePrefix << "_d"
<< (modulePos * numUnitsPerReadout + iReadout) << "_f"
<< iFile << '_' << fileIndex << ".h5";
std::string srcFileName = os.str();
LOG(logDEBUG1) << srcFileName;
// find relative path
std::string relative_srcFileName = srcFileName;
{
size_t p = srcFileName.rfind('/', srcFileName.length());
if (p != std::string::npos)
relative_srcFileName = (srcFileName.substr(
p + 1, srcFileName.length() - p));
}
// source dataset name
std::ostringstream osfn;
osfn << "/data";
if (numImages > 1)
osfn << "_f" << std::setfill('0') << std::setw(12) << iFile;
std::string srcDatasetName = osfn.str();
// source dataspace
hsize_t srcDims[3] = {nDimx, nDimy, nDimz};
hsize_t srcDimsMax[3] = {H5S_UNLIMITED, nDimy, nDimz};
DataSpace srcDataSpace(3, srcDims, srcDimsMax);
hsize_t srcDimsPara[1] = {nDimx};
hsize_t srcDimsMaxPara[1] = {H5S_UNLIMITED};
DataSpace srcDataSpacePara(1, srcDimsPara, srcDimsMaxPara);
// mapping of property list
plist.setVirtual(vdsDataSpace, relative_srcFileName.c_str(),
srcDatasetName.c_str(), srcDataSpace);
for (unsigned int p = 0; p < paraSize; ++p) {
plistPara[p].setVirtual(
vdsDataSpacePara, relative_srcFileName.c_str(),
parameterNames[p].c_str(), srcDataSpacePara);
}
// H5Sclose(srcDataspace);
// H5Sclose(srcDataspace_para);
if (!gotthard25um) {
startLocation[2] += nDimz;
if (startLocation[2] >= (numModZ * nDimz)) {
startLocation[2] = 0;
startLocation[1] += nDimy;
}
}
startLocationPara[1]++;
}
framesSaved += nDimx;
}
// datasets
DataSet vdsDataSet(fd->createDataSet(dataSetName.c_str(), dataType,
vdsDataSpace, plist));
for (unsigned int p = 0; p < paraSize; ++p) {
DataSet vdsDataSetPara(fd->createDataSet(
parameterNames[p].c_str(), parameterDataTypes[p],
vdsDataSpacePara, plistPara[p]));
}
fd->close();
} catch (const Exception &error) {
error.printErrorStack();
if (fd) {
fd->close();
}
throw sls::RuntimeError(
"Could not create/overwrite virtual HDF5 handles");
}
if (!silentMode) {
LOG(logINFO) << "Virtual File: " << fileName;
}
return std::array<std::string, 2>{fileName, dataSetName};
}
#endif
} // namespace masterFileUtility

View File

@ -1,50 +0,0 @@
// SPDX-License-Identifier: LGPL-3.0-or-other
// Copyright (C) 2021 Contributors to the SLS Detector Package
#pragma once
#include "MasterAttributes.h"
#ifdef HDF5C
#include "H5Cpp.h"
#include <mutex>
#ifndef H5_NO_NAMESPACE
using namespace H5;
#endif
#endif
namespace masterFileUtility {
std::string CreateMasterBinaryFile(const std::string &filePath,
const std::string &fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode,
MasterAttributes *attr);
#ifdef HDF5C
void LinkHDF5FileInMaster(const std::string &masterFileName,
const std::string &dataFilename,
const std::string &dataSetname,
const std::vector<std::string> parameterNames,
const bool silentMode, std::mutex *hdf5LibMutex);
std::string CreateMasterHDF5File(const std::string &filePath,
const std::string &fileNamePrefix,
const uint64_t fileIndex,
const bool overWriteEnable,
const bool silentMode, MasterAttributes *attr,
std::mutex *hdf5LibMutex);
std::array<std::string, 2> CreateVirtualHDF5File(
const std::string &filePath, const std::string &fileNamePrefix,
const uint64_t fileIndex, const bool overWriteEnable, const bool silentMode,
const int modulePos, const int numUnitsPerReadout,
const uint32_t maxFramesPerFile, const uint64_t numImages,
const uint32_t nPixelsX, const uint32_t nPixelsY,
const uint32_t dynamicRange, const uint64_t numImagesCaught,
const int numModX, const int numModY, const DataType dataType,
const std::vector<std::string> parameterNames,
const std::vector<DataType> parameterDataTypes, std::mutex *hdf5LibMutex,
bool gotthard25um);
#endif
} // namespace masterFileUtility

View File

@ -18,7 +18,7 @@
// versions // versions
#define HDF5_WRITER_VERSION (6.4) // 1 decimal places #define HDF5_WRITER_VERSION (6.4) // 1 decimal places
#define BINARY_WRITER_VERSION (7.0) // 1 decimal places #define BINARY_WRITER_VERSION (6.4) // 1 decimal places
#define MAX_FRAMES_PER_FILE 20000 #define MAX_FRAMES_PER_FILE 20000
#define SHORT_MAX_FRAMES_PER_FILE 100000 #define SHORT_MAX_FRAMES_PER_FILE 100000

View File

@ -34,8 +34,8 @@ TEST_CASE("Push pop") {
for (size_t i = 0; i != vec.size(); ++i) { for (size_t i = 0; i != vec.size(); ++i) {
fifo.push(p); fifo.push(p);
++p; ++p;
CHECK(fifo.getDataValue() == (int)(i + 1)); CHECK(fifo.getDataValue() == i + 1);
CHECK(fifo.getFreeValue() == (int)(4 - i)); CHECK(fifo.getFreeValue() == 4 - i);
} }
CHECK(fifo.isEmpty() == false); CHECK(fifo.isEmpty() == false);
@ -44,8 +44,8 @@ TEST_CASE("Push pop") {
for (size_t i = 0; i != vec.size(); ++i) { for (size_t i = 0; i != vec.size(); ++i) {
fifo.pop(p); fifo.pop(p);
CHECK(*p == vec[i]); CHECK(*p == vec[i]);
CHECK(fifo.getDataValue() == (int)(4 - i)); CHECK(fifo.getDataValue() == 4 - i);
CHECK(fifo.getFreeValue() == (int)(i + 1)); CHECK(fifo.getFreeValue() == i + 1);
} }
CHECK(fifo.isEmpty() == true); CHECK(fifo.isEmpty() == true);

View File

@ -6,10 +6,10 @@
#define APIRECEIVER 0x211124 #define APIRECEIVER 0x211124
#define APIGUI 0x211124 #define APIGUI 0x211124
#define APIEIGER 0x220324 #define APICTB 0x220902
#define APICTB 0x220328 #define APIGOTTHARD 0x220902
#define APIGOTTHARD 0x220328 #define APIGOTTHARD2 0x220902
#define APIGOTTHARD2 0x220328 #define APIJUNGFRAU 0x220902
#define APIJUNGFRAU 0x220328 #define APIMYTHEN3 0x220902
#define APIMOENCH 0x220328 #define APIMOENCH 0x220902
#define APIMYTHEN3 0x220404 #define APIEIGER 0x220902