RaptorEagleV/raptor_eagle_ccd.cpp
2024-12-03 18:10:44 +03:00

866 lines
25 KiB
C++

#include <cmath>
#include <cstring>
#include "raptor_eagle_cameralink.h"
#include "raptor_eagle_ccd.h"
#include "raptor_eagle_exception.h"
#include <common/adc_utils.h>
namespace details
{
// compute checksum as XOR operation along elements of byte array
template <std::ranges::input_range R>
auto computeChecksum(const R& bytes, bool final_etx = true)
requires std::convertible_to<std::ranges::range_value_t<R>, char>
{
std::ranges::range_value_t<R> res = 0;
if (std::ranges::size(bytes) == 0) {
return res;
}
for (auto& byte : bytes) {
res ^= byte;
}
if (final_etx) {
res ^= CL_ETX;
}
return res;
}
// assume that least significant byte is the last one in 'bytes'
// only the first 5 elements of the input range are taken
template <std::ranges::input_range R>
size_t convert40BitToCounts(const R& bytes)
requires std::same_as<std::ranges::range_value_t<R>, unsigned char>
{
// size_t counts = 0, i = std::ranges::size(bytes);
// for (auto& byte : bytes| std::views::take(5)) {
// counts += byte << (--i * 8);
// }
if (std::ranges::size(bytes) == 0)
return 0;
size_t counts = *bytes.begin();
for (auto& byte : bytes | std::views::drop(1) | std::views::take(4)) {
counts <<= 8;
counts |= byte;
}
return counts;
}
// NOTE: it is assumed little-endian host's platform!!!
// return an range with least significant byte in the end of the range
template <std::ranges::output_range<unsigned char> R = std::vector<unsigned char>>
R convertCountsTo40Bit(uint64_t counts)
{
R res;
auto sp = std::span(reinterpret_cast<unsigned char*>(&counts), 8);
// least significant byte in the end of the output range
std::ranges::copy(sp | std::views::take(5) | std::views::reverse, std::back_inserter(res));
return res;
}
// assume that least significant byte is the last one in 'bytes'
// only the first 2 elements of the input range are taken
template <std::ranges::input_range R>
uint16_t convert12BitToUInt(const R& bytes)
requires std::same_as<std::ranges::range_value_t<R>, unsigned char>
{
if (std::ranges::size(bytes) == 0)
return 0;
auto v = bytes | std::views::reverse | std::views::take(2);
if (std::ranges::size(bytes) > 1) {
return *v.begin() + ((*(++v.begin()) & 0x0F) << 8);
} else {
return *v.begin();
}
}
// NOTE: it is assumed little-endian host's platform!!!
// return an range with least significant byte in the end of the range
template <std::ranges::output_range<unsigned char> R = std::vector<unsigned char>>
R convertUIntTo12Bit(uint16_t counts)
{
R res;
auto sp = std::span(reinterpret_cast<unsigned char*>(&counts), 2);
// least significant byte in the end of the output range
std::ranges::copy(sp | std::views::reverse, std::back_inserter(res));
return res;
}
} // namespace details
#define DEFAULT_EPIX_VIDEO_FMT_FILE "raptor_eagle-v.fmt"
/* CONSTRUCTORS AND DESTRUCTOR */
RaptorEagleCCD::RaptorEagleCCD(const adc::traits::adc_input_char_range auto& epix_video_fmt_filename,
std::shared_ptr<spdlog::logger> logger)
: base_t("EagleCCD"),
adc::AdcSpdlogLogger(logger),
_epixFmtVideoFilename(),
_cameraUnitmap(1), // by default only the single camera
_clCommandAckBit(1), // enable by default (at camera boot up)
_clChecksumBit(1) // enable by default (at camera boot up)
{
addMarkToPattern("EAGLE-CCD");
std::ranges::copy(epix_video_fmt_filename, std::back_inserter(_epixFmtVideoFilename));
logDebug("CTOR: Create RaptorEagleCCD class instance");
if (_epixFmtVideoFilename.empty()) {
logDebug("Video format filename is not set! Use of default: {}", DEFAULT_EPIX_VIDEO_FMT_FILE);
} else {
logDebug("Set video format filename: {}", _epixFmtVideoFilename);
}
}
RaptorEagleCCD::RaptorEagleCCD(std::shared_ptr<spdlog::logger> logger)
: RaptorEagleCCD(std::string_view(), std::move(logger))
{
}
RaptorEagleCCD::~RaptorEagleCCD()
{
logDebug("DTOR: Delete RaptorEagleCCD class instance");
}
/* PUBLIC METHODS */
/* system state get/set */
std::bitset<8> RaptorEagleCCD::getSystemState()
{
std::lock_guard lock_guard(_camlinkMutex);
byte_seq_t ans;
clWrite({0x49});
clReadAndCheckAck(ans);
std::bitset<8> bits{ans[0]};
logDebug("Get system state as 0b{} bits", bits.to_string());
return bits;
}
void RaptorEagleCCD::setSystemState(const std::bitset<8>& bits)
{
std::lock_guard lock_guard(_camlinkMutex);
logDebug("Try to set system state to 0b{} bits", bits.to_string());
uint8_t status = static_cast<uint8_t>(bits.to_ulong());
clWrite({0x4F, status});
clReadAndCheckAck();
}
void RaptorEagleCCD::setSystemStateBit(const size_t pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getSystemState();
logDebug("Set system state bit {}", details::cl_system_status_bit(pos));
bits.set(pos);
setSystemState(bits);
}
void RaptorEagleCCD::clearSystemStateBit(const size_t pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getSystemState();
logDebug("Clear system state bit {}", details::cl_system_status_bit(pos));
bits.reset(pos);
setSystemState(bits);
}
void RaptorEagleCCD::flipSystemStateBit(const size_t pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getSystemState();
logDebug("Flip system state bit {}", details::cl_system_status_bit(pos));
bits.flip(pos);
setSystemState(bits);
}
// FPGS control register get/set
std::bitset<8> RaptorEagleCCD::getFPGAState()
{
std::lock_guard log_guard(_camlinkMutex);
auto ans = readRegisters({0x00});
std::bitset<8> bits{ans[0]};
logDebug("Get FPGS control register as 0b{} bits", bits.to_string());
return bits;
}
void RaptorEagleCCD::setFPGAState(const std::bitset<8>& bits)
{
std::lock_guard lock_guard(_camlinkMutex);
logDebug("Try to set FPGA control register to 0b{} bits", bits.to_string());
uint8_t status = static_cast<uint8_t>(bits.to_ulong());
writeRegisters({0x00}, {status});
}
void RaptorEagleCCD::setFPGAStateBit(const size_t pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getFPGAState();
logDebug("Set FPGA control register bit {}", details::cl_fpga_ctrl_reg_bit(pos));
bits.set(pos);
setFPGAState(bits);
}
void RaptorEagleCCD::clearFPGAStateBit(const size_t pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getFPGAState();
logDebug("Clear FPGA control register bit {}", details::cl_fpga_ctrl_reg_bit(pos));
bits.reset(pos);
setFPGAState(bits);
}
void RaptorEagleCCD::flipFPGAStateBit(const size_t pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getFPGAState();
logDebug("Flip FPGA control register bit {}", details::cl_fpga_ctrl_reg_bit(pos));
bits.flip(pos);
setFPGAState(bits);
}
/* PRIVATE METHODS */
void RaptorEagleCCD::initCamera(int unitmap)
{
logInfo("Try to init camera with unitmap: {} ...", unitmap);
if (unitmap < 0) {
throw std::system_error(RaptorEagleCCDError::ERROR_INVALID_UNITMAP);
}
_cameraUnitmap = unitmap;
xclibApiCall(pxd_serialConfigure(_cameraUnitmap, 0, CL_DEFAULT_BAUD_RATE, CL_DEFAULT_DATA_BITS, 0,
CL_DEFAULT_STOP_BIT, 0, 0, 0),
std::format("pxd_serialConfigure({}, 0, {}, {}, 0, {}, 0, 0, 0)", _cameraUnitmap, CL_DEFAULT_BAUD_RATE,
CL_DEFAULT_DATA_BITS, CL_DEFAULT_STOP_BIT));
logInfo("Camera with unitmap '{}' is initialized", _cameraUnitmap);
}
void RaptorEagleCCD::openPIXCI()
{
if (_epixFmtVideoFilename.size()) {
xclibApiCall(pxd_PIXCIopen("", nullptr, _epixFmtVideoFilename.c_str()),
std::format("pxd_PIXCIopen(\"\", NULL, {})", _epixFmtVideoFilename));
} else {
xclibApiCall(pxd_PIXCIopen("", "DEFAULT", ""), "pxd_PIXCIopen(\"\", \"DEFAULT\", \"\")");
#include DEFAULT_EPIX_VIDEO_FMT_FILE // exported from XCAP (Linux 64-bit!): bin 1x1, full CCD frame
pxd_videoFormatAsIncludedInit(0);
xclibApiCall(pxd_videoFormatAsIncluded(0), "pxd_videoFormatAsIncluded(0)");
}
}
void RaptorEagleCCD::closePIXCI()
{
// no exception here!!!
xclibApiCall<true>(pxd_PIXCIclose(), "pxd_PIXCIclose()");
}
/* SYSTEM STATUS */
/*------------*/
const RaptorEagleCCD::SystemStatus RaptorEagleCCD::getSystemStatus()
{
std::lock_guard lock_guard(_camlinkMutex);
byte_seq_t ans;
clWrite({0x49});
clReadAndCheckAck(ans);
SystemStatus status;
status.ackEnabled = ans[0] & CL_SYSTEM_STATUS_ACK;
status.checkSumEnabled = ans[0] & CL_SYSTEM_STATUS_CK_SUM;
status.bootedFPGA = ans[0] & CL_SYSTEM_STATUS_FPGA_BOOT_OK;
status.commsFPGAEnabled = ans[0] & CL_SYSTEM_STATUS_FPGA_EEPROM_COMMS;
status.holdFPGAInReset = !(ans[0] & CL_SYSTEM_STATUS_FPGA_RST_HOLD); // hold in RESET if bit is 0
return status;
}
void RaptorEagleCCD::setSystemStatus(const RaptorEagleCCD::SystemStatus& status)
{
uint8_t st = 0;
if (status.ackEnabled)
st |= CL_SYSTEM_STATUS_ACK;
if (status.checkSumEnabled)
st |= CL_SYSTEM_STATUS_CK_SUM;
if (status.bootedFPGA)
st |= CL_SYSTEM_STATUS_FPGA_BOOT_OK;
if (status.commsFPGAEnabled)
st |= CL_SYSTEM_STATUS_FPGA_EEPROM_COMMS;
if (status.holdFPGAInReset)
st &= ~CL_SYSTEM_STATUS_FPGA_RST_HOLD;
setSystemStatus(st);
}
void RaptorEagleCCD::setSystemStatus(const uint8_t& status)
{
std::lock_guard lock_guard(_camlinkMutex);
clWrite({0x4F, status});
clReadAndCheckAck();
}
/* CameraLink-RELATED METHODS */
size_t RaptorEagleCCD::clRead(byte_seq_t& bytes)
{
std::lock_guard lock_guard(_camlinkMutex);
size_t nbytes;
// how many byte are available
xclibApiCall(nbytes = pxd_serialRead(_cameraUnitmap, 0, nullptr, 0),
std::format("pxd_serialRead({}, 0, NULL, 0)", _cameraUnitmap));
if (!nbytes) {
logWarn("There are no bytes in Rx-buffer! Nothing to do!");
return 0;
}
nbytes += _clCommandAckBit + _clChecksumBit;
if (bytes.size() < nbytes) {
bytes.resize(nbytes);
}
xclibApiCall(pxd_serialRead(_cameraUnitmap, 0, (char*)bytes.data(), nbytes),
std::format("pxd_serialRead({}, 0, {}, {})", _cameraUnitmap, (void*)bytes.data(), nbytes));
if (_loggerSPtr->level() == spdlog::level::trace) {
std::string s;
adc::utils::AdcCharRangeFromValueRange(s, bytes, std::string_view(", "));
logTrace("Received from controller: [{}]", s);
}
return nbytes;
}
size_t RaptorEagleCCD::clReadAndCheckAck(byte_seq_t& bytes)
{
std::lock_guard lock_guard(_camlinkMutex);
auto nbytes = clRead(bytes);
if (_clCommandAckBit && nbytes) {
auto ack = *(bytes.end() - 1 - _clChecksumBit);
if (ack != CL_ETX) {
throw std::error_code(ack, RaptorEagleControllerErrorCategory::get());
}
}
return nbytes;
}
size_t RaptorEagleCCD::clReadAndCheckAck()
{
byte_seq_t bytes;
return clReadAndCheckAck(bytes);
}
// 'bytes' must contain only data without trailing ETX and checksum bytes!
size_t RaptorEagleCCD::clWrite(const byte_seq_t& bytes)
{
std::lock_guard lock_guard(_camlinkMutex);
static unsigned char etx_checksum_bytes[] = {CL_ETX, 0xFF};
if (bytes.empty()) {
logWarn("An empty transmitted byte sequence! Nothing to do!");
return 0;
}
if (_loggerSPtr->level() == spdlog::level::trace) {
std::string s;
adc::utils::AdcCharRangeFromValueRange(s, bytes, std::string_view(", "));
logTrace("Send to controller: [{}]", s);
}
size_t nbytes, tr_nbytes = 1 + _clChecksumBit;
// how many bytes are available in Tx-buffer
xclibApiCall(nbytes = pxd_serialWrite(_cameraUnitmap, 0, nullptr, 0),
std::format("pxd_serialWrite({}, 0, NULL, 0)", _cameraUnitmap));
if (nbytes) {
if (nbytes < (bytes.size() + tr_nbytes)) {
logWarn(
"Not enough of available space in the internal Tx-buffer (needs = {}, available = {})! Nothing to do!",
bytes.size() + tr_nbytes, nbytes);
nbytes = 0;
} else {
if (_clChecksumBit) {
etx_checksum_bytes[1] = details::computeChecksum(bytes);
}
xclibApiCall(
nbytes = pxd_serialWrite(_cameraUnitmap, 0, (char*)bytes.data(), bytes.size()),
std::format("pxd_serialWrite({}, 0, {}, {})", _cameraUnitmap, (void*)bytes.data(), bytes.size()));
if (nbytes != bytes.size()) {
throw std::error_code(RaptorEagleCCDError::ERROR_CAMLINK_WRITE);
}
// send trailing ETX and possible checksum bytes
size_t n;
if (tr_nbytes > 1) {
logDebug("Write trailing ETX and checksum bytes");
} else {
logDebug("Write trailing ETX byte");
}
xclibApiCall(
n = pxd_serialWrite(_cameraUnitmap, 0, (char*)etx_checksum_bytes, tr_nbytes),
std::format("pxd_serialWrite({}, 0, {}, {})", _cameraUnitmap, (void*)etx_checksum_bytes, tr_nbytes));
if (n != tr_nbytes) {
throw std::error_code(RaptorEagleCCDError::ERROR_CAMLINK_WRITE);
}
nbytes += n;
}
} else {
logWarn("No available space in the internal Tx-buffer! Nothing to do!");
}
return nbytes;
}
RaptorEagleCCD::byte_seq_t RaptorEagleCCD::readRegisters(const RaptorEagleCCD::byte_seq_t& addrs,
byte_seq_t set_addr_cmd)
{
// to protect in multi-threading environment (multiple read-write operations, see below)
std::lock_guard lock_guard(_camlinkMutex);
byte_seq_t reg_vals, ans(3);
if (addrs.empty()) {
logWarn("Registers addresses array is an empty! Nothing to do!");
return reg_vals;
}
// from Eagle V 4240 instruction manual (rev 1.1)
byte_seq_t set_addr_comm = std::move(set_addr_cmd); // set address controller command
static const byte_seq_t read_reg_comm{0x53, 0xE1, 0x01}; // read register controller command
reg_vals.resize(addrs.size());
size_t i = 0;
for (auto& addr : addrs) {
// set address
set_addr_comm[3] = addr;
clWrite(set_addr_comm);
clReadAndCheckAck(ans);
// get value
clWrite(read_reg_comm);
clReadAndCheckAck(ans);
reg_vals[i++] = ans[0];
}
return reg_vals;
}
void RaptorEagleCCD::writeRegisters(const byte_seq_t& addrs, const byte_seq_t& values)
{
// to protect in multi-threading environment (multiple read-write operations, see below)
std::lock_guard lock_guard(_camlinkMutex);
if (addrs.empty() || values.empty()) {
logWarn("Registers addresses or values array is an empty! Nothing to do!");
return;
}
size_t N = addrs.size() < values.size() ? addrs.size() : values.size();
// from Eagle V 4240 instruction manual (rev 1.1)
byte_seq_t comm{0x53, 0xE0, 0x02, 0x00, 0x00};
for (size_t i = 0; i < N; ++i) {
comm[3] = addrs[i];
comm[4] = values[i];
clWrite(comm);
clReadAndCheckAck(); // no data from controller here just check answer for errors
}
}
/* CREATE COMMANDS AND ATTRIBUTES */
void RaptorEagleCCD::initAttrComm()
{
/* commands */
/* attributes */
addAttribute(
CAMERA_ATTR_CAMLINK_SETUP,
[this]() {
logTrace("Return CameraLink setup bits (current values: command-ack = {}, checksum = {})", _clCommandAckBit,
_clChecksumBit);
return std::vector<uint8_t>({_clCommandAckBit, _clChecksumBit});
},
[this](const std::vector<uint8_t>& setup) {
logDebug("Try to set CameraLink setup bits ...");
if (setup.size() < 2) {
throw std::error_code(RaptorEagleCCDError::ERROR_INVALID_ATTR_VALUE);
}
_clCommandAckBit = setup[0] ? 1 : 0;
_clChecksumBit =
(setup[1] && _clCommandAckBit) ? 1 : 0; // checksum will be enabled only if command ack is set
logDebug("Set CameraLink setup bits to: command-ack = {}, checksum = {}", _clCommandAckBit, _clChecksumBit);
});
// exposure time
addAttribute(
CAMERA_ATTR_EXPTIME,
[this]() {
auto bytes = readRegisters(CL_EXPTIME_ADDR);
size_t counts = details::convert40BitToCounts(bytes);
double exp_time = counts * 2.5E-8; // counts of 25nsec ticks
logTrace("Return acquision duration (current value is {} seconds ({} 25nsec ticks))", exp_time, counts);
return exp_time;
},
[this](const double& exp_time) {
logDebug("Try to set acquisition duration to {} seconds ...", exp_time);
double etime;
if (exp_time < 0.0) {
logWarn("Acquisition duration must be non-negative!");
etime = 0.0;
} else if (exp_time > EAGLE_CAMERA_MAX_EXPTIME) {
logWarn("Acquisition duration must not be greater than {} seconds!", EAGLE_CAMERA_MAX_EXPTIME);
etime = EAGLE_CAMERA_MAX_EXPTIME;
} else {
etime = exp_time;
}
size_t counts = static_cast<size_t>(std::round(etime / 2.5E-8));
auto bytes = details::convertCountsTo40Bit(counts);
writeRegisters(CL_EXPTIME_ADDR, bytes);
logDebug("Acquisition duration is set to {} second ({} 25nsec ticks)", etime, counts);
});
// frame rate
addAttribute(
CAMERA_ATTR_FRAME_RATE,
[this]() {
auto bytes = readRegisters(CL_FRAMERATE_ADDR);
size_t counts = details::convert40BitToCounts(bytes);
size_t rate = counts * 40; // in MHz
logTrace("Return frame rate (current value is {} MHz ({} 40MHz ticks))", rate, counts);
return rate;
},
[this](const size_t& rate) {
logDebug("Try to set frame rate to {} MHz ...", rate);
size_t r;
if (rate < 0) {
logWarn("Frame rate must be non-negative!");
r = 0;
} else if (rate > EAGLE_CAMERA_MAX_FRAMERATE) {
logWarn("Frame rate must not be greater than {} MHz!", EAGLE_CAMERA_MAX_FRAMERATE);
r = EAGLE_CAMERA_MAX_FRAMERATE;
} else {
r = rate;
}
size_t counts = r / 40;
auto bytes = details::convertCountsTo40Bit(counts);
writeRegisters(CL_FRAMERATE_ADDR, bytes);
logDebug("Frame rate is set to {} MHz ({} 40MHz ticks)", r, counts);
});
// number of exposures
addAttribute(
CAMERA_ATTR_NEXP,
[this]() {
logTrace("Return number of frames in acquisition sequence (current value is {})", _frameNumbers);
return _frameNumbers;
},
[this](const size_t& nframes) {
_frameNumbers = nframes;
logDebug("Number of frames in acquisition sequence is set to {}", _frameNumbers);
});
// helper to setup 12-bit register attributes
auto create12BitAttr = [this](std::string_view name, auto reg_addrs, auto&& validator, std::string_view log_mark) {
return RaptorEagleCCD::attribute_t(
name,
[this, reg_addrs, log_mark]() {
auto bytes = readRegisters(reg_addrs);
uint16_t v = details::convert12BitToUInt(bytes);
logTrace("Return {} (current value: {})", log_mark, v);
return v;
},
[this, reg_addrs, log_mark,
wrapper = adc::traits::adc_pf_wrapper(std::forward<decltype(validator)>(validator))](
const uint16_t& val) mutable {
logDebug("Try to set {} to {} ...", log_mark, val);
// call perfectly-forwarded validator
auto v_res = std::forward<std::tuple_element_t<0, decltype(wrapper)>>(std::get<0>(wrapper))(val);
if (v_res.second.size()) { // warning
logWarn("{}", v_res.second);
}
auto bytes = details::convertUIntTo12Bit(v_res.first);
writeRegisters(reg_addrs, bytes);
logDebug("{} is set to {}", log_mark, v_res.first);
});
};
// ROI left
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_STARTX, CL_ROI_STARTX_ADDR,
[this](const uint16_t& val) { // validator
std::pair<uint16_t, std::string> res{val, ""};
if (val < 1) {
res.first = 1;
res.second = "The ROI X-offset must start from 1 (FITS notation)";
} else if (val > _dimCCD[0]) {
res.first = _dimCCD[0];
res.second = std::format(
"The ROI X-offset must not be greater than CCD X-dimension of {} pixels (FITS notation)",
_dimCCD[0]);
}
return res;
},
"ROI X-offset"));
// ROI top
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_STARTY, CL_ROI_STARTY_ADDR,
[this](const uint16_t& val) { // validator
std::pair<uint16_t, std::string> res{val, ""};
if (val < 1) {
res.first = 1;
res.second = "The ROI Y-offset must start from 1 (FITS notation)";
} else if (val > _dimCCD[1]) {
res.first = _dimCCD[1];
res.second = std::format(
"The ROI Y-offset must not be greater than CCD Y-dimension of {} pixels (FITS notation)",
_dimCCD[1]);
}
return res;
},
"ROI Y-offset"));
// ROI width
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_WIDTH, CL_ROIWIDTH_ADDR,
[this](const uint16_t& val) { // validator
std::pair<uint16_t, std::string> res{val, ""};
if (val < 1) {
res.first = 1;
res.second = "The ROI width must start from 1";
} else if (val > _dimCCD[0]) {
res.first = _dimCCD[0];
res.second = std::format(
"The ROI width must not be greater than CCD dimension of {} pixels (FITS notation)", _dimCCD[0]);
}
return res;
},
"ROI width"));
// ROI height
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_HEIGHT, CL_ROIHEIGHT_ADDR,
[this](const uint16_t& val) { // validator
std::pair<uint16_t, std::string> res{val, ""};
// ROI height can be 0 (see Eagle V 4240 instruction manual)
if (val > _dimCCD[1]) {
res.first = _dimCCD[1];
res.second = std::format(
"The ROI height must not be greater than CCD dimension of {} pixels (FITS notation)", _dimCCD[1]);
}
return res;
},
"ROI height"));
// X-bin
addAttribute(create12BitAttr(
CAMERA_ATTR_XBIN, CL_XBIN_ADDR,
[this](const uint16_t& val) { // validator (1-32, 64)
std::pair<uint16_t, std::string> res{val, ""};
if (val < 1) {
res.first = 1;
res.second = "The XBIN must start from 1";
} else if ((val > EAGLE_CAMERA_MAX_XBIN[0]) && (val < EAGLE_CAMERA_MAX_XBIN[1])) {
// set to the closest
res.first = (val - EAGLE_CAMERA_MAX_XBIN[0]) < (EAGLE_CAMERA_MAX_XBIN[1] - val)
? EAGLE_CAMERA_MAX_XBIN[0]
: EAGLE_CAMERA_MAX_XBIN[1];
res.second = std::format("The XBIN must not be within {} and {}", EAGLE_CAMERA_MAX_XBIN[0],
EAGLE_CAMERA_MAX_XBIN[1]);
} else if (val > EAGLE_CAMERA_MAX_XBIN[1]) {
res.first = EAGLE_CAMERA_MAX_XBIN[1];
res.second = std::format("The XBIN must not be greater than {}", EAGLE_CAMERA_MAX_XBIN[1]);
}
return res;
},
"XBIN"));
// Y-bin
addAttribute(create12BitAttr(
CAMERA_ATTR_YBIN, CL_YBIN_ADDR,
[this](const uint16_t& val) { // validator (1-32, 64)
std::pair<uint16_t, std::string> res{val, ""};
if (val < 1) {
res.first = 1;
res.second = "The YBIN must start from 1";
} else if ((val > EAGLE_CAMERA_MAX_YBIN[0]) && (val < EAGLE_CAMERA_MAX_YBIN[1])) {
// set to the closest
res.first = (val - EAGLE_CAMERA_MAX_YBIN[0]) < (EAGLE_CAMERA_MAX_YBIN[1] - val)
? EAGLE_CAMERA_MAX_YBIN[0]
: EAGLE_CAMERA_MAX_YBIN[1];
res.second = std::format("The YBIN must not be within {} and {}", EAGLE_CAMERA_MAX_YBIN[0],
EAGLE_CAMERA_MAX_YBIN[1]);
} else if (val > EAGLE_CAMERA_MAX_YBIN[1]) {
res.first = EAGLE_CAMERA_MAX_YBIN[1];
res.second = std::format("The YBIN must not be greater than {}", EAGLE_CAMERA_MAX_XBIN[1]);
}
return res;
},
"YBIN"));
}