RaptorEagleV/raptor_eagle_ccd.cpp
Timur A. Fatkhullin c1b7d249da start development branch.
rewrite image buffer managment (dynamic ring buffer, allocation of
buffers at initialization of camera, no allocation of image buffer per
acquisition process)
2024-12-27 18:41:46 +03:00

2128 lines
73 KiB
C++

#include <cmath>
#include <csignal>
#include <cstring>
#include <filesystem>
#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;
}
std::string formatByteArr(const std::ranges::range auto& bytes, std::string_view delim = ", ")
requires std::integral<std::ranges::range_value_t<decltype(bytes)>>
{
std::string res;
using el_t = std::make_unsigned_t<std::ranges::range_value_t<decltype(bytes)>>;
auto sz = std::ranges::size(bytes);
if (!sz) {
return res;
}
for (el_t el : bytes | std::views::take(sz - 1)) {
res += std::format("0x{:02X}{}", el, delim);
}
res += std::format("0x{:02X}", *(bytes.end() - 1));
return res;
}
} // namespace details
/***********************************************************/
/* ======= RaptorEagleCCD CLASS IMPLEMENTATION ======= */
/***********************************************************/
#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()) {
logInfo("Video format filename is not given! Use of default: {}", DEFAULT_EPIX_VIDEO_FMT_FILE);
} else {
logInfo("Set video format filename: {}", _epixFmtVideoFilename);
}
AcquisitionProcess::serverPtr = this;
initAttrComm();
openPIXCI();
}
RaptorEagleCCD::RaptorEagleCCD(std::shared_ptr<spdlog::logger> logger)
: RaptorEagleCCD(std::string_view(), std::move(logger))
{
}
RaptorEagleCCD::~RaptorEagleCCD()
{
closePIXCI();
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());
_clCommandAckBit = bits.test(CL_SYSTEM_STATUS_ACK_BIT) ? 1 : 0;
_clChecksumBit = bits.test(CL_SYSTEM_STATUS_CK_SUM_BIT) ? 1 : 0;
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();
_clCommandAckBit = bits.test(CL_SYSTEM_STATUS_ACK_BIT) ? 1 : 0;
_clChecksumBit = bits.test(CL_SYSTEM_STATUS_CK_SUM_BIT) ? 1 : 0;
}
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);
}
// FPGA 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 FPGA 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);
}
std::bitset<8> RaptorEagleCCD::getTriggerRegister()
{
std::lock_guard log_guard(_camlinkMutex);
auto bytes = readRegisters({0xD4});
std::bitset<8> bits{bytes[0]};
logDebug("Get trigger register as 0b{}", bits.to_string());
return bits;
}
std::chrono::utc_clock::time_point RaptorEagleCCD::setTriggerRegister(const std::bitset<8> bits)
{
std::lock_guard lock_guard(_camlinkMutex);
logDebug("Try to set trigger register to 0b{} bits", bits.to_string());
uint8_t reg = static_cast<uint8_t>(bits.to_ulong());
auto tm = std::chrono::utc_clock::now();
writeRegisters({0xD4}, {reg});
return tm;
}
std::chrono::utc_clock::time_point RaptorEagleCCD::setTriggerRegisterBit(const size_t bit_pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getTriggerRegister();
logDebug("Try to set '{}' trigger register bit", details::cl_trigger_register_bit(bit_pos));
bits.set(bit_pos);
return setTriggerRegister(bits);
}
std::chrono::utc_clock::time_point RaptorEagleCCD::clearTriggerRegisterBit(const size_t bit_pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getTriggerRegister();
logDebug("Try to clear '{}' trigger register bit", details::cl_trigger_register_bit(bit_pos));
bits.reset(bit_pos);
return setTriggerRegister(bits);
}
std::chrono::utc_clock::time_point RaptorEagleCCD::flipTriggerRegisterBit(const size_t bit_pos)
{
std::lock_guard lock_guard(_camlinkMutex);
auto bits = getTriggerRegister();
logDebug("Try to flip '{}' trigger register bit", details::cl_trigger_register_bit(bit_pos));
bits.flip(bit_pos);
return setTriggerRegister(bits);
}
/* PRIVATE METHODS */
bool RaptorEagleCCD::initCamera(int unitmap)
{
logInfo("Try to init camera with unitmap: {} ...", unitmap);
if (unitmap < 0) {
throw std::system_error(RaptorEagleCCDError::ERROR_INVALID_UNITMAP);
}
std::string status = (*this)[CAMERA_ATTR_CAMERA_STATUS];
if (status != CAMERA_ATTR_CAMERA_STATUS_IDLE) {
logWarn("It seems camera current status is not IDLE! Abort possible exposure!");
(*this)[CAMERA_CMD_ABORT_EXP];
// _cameraStatus = CAMERA_ATTR_CAMERA_STATUS_IDLE;
}
AcquisitionProcess::isAcqInProgress = false; // ??????!!!!!!!!!!!
_cameraUnitmap = unitmap;
// configure CameraLink serial connection
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));
bool ok = resetFPGA();
if (!ok) {
logError("Cannot reboot FPGA!");
return ok;
}
// ok = resetMicro();
// if (!ok) {
// logError("Cannot reset microcontroller!");
// return ok;
// }
getSystemState();
getHardwareInfo();
getMicroVersion();
getFPGAVersion();
xclibApiCall(_dimCCD[0] = pxd_imageXdim(), "pxd_imageXdim()");
xclibApiCall(_dimCCD[1] = pxd_imageYdim(), "pxd_imageYdim()");
xclibApiCall(_bitsPerPixel = pxd_imageBdim(), "pxd_imageBdim()");
xclibApiCall(_imageFrameBuffNumber = pxd_imageZdim(), "pxd_imageZdim()");
// memory
if (_acqRingBuffer.empty()) { // the first init. allocate ring buffer
logDebug("Allocate memory for acquisition ring buffer");
_acqRingBuffer.resize(DEFAULT_ACQ_RING_BUFFER_SIZE);
try {
for (auto& uptr : _acqRingBuffer) {
uptr.reset(new ushort[_dimCCD[0] * _dimCCD[1]]); // full CCD frame
_acqRingFreeBufferPtrs.push(uptr.get());
}
} catch (const std::bad_alloc&) {
logError("Cannot allocate memory for ring buffer!");
return false;
}
} else { // re-initialization. just resize ring buffer to initial default size
_acqRingBuffer.resize(DEFAULT_ACQ_RING_BUFFER_SIZE);
_acqRingFreeBufferPtrs = std::queue<ushort*>();
for (auto& uptr : _acqRingBuffer) {
_acqRingFreeBufferPtrs.push(uptr.get());
}
}
logDebug("------- CCD and grabber hardware info -------");
logDebug("CCD full-frame dimension [{}, {}] pixels", _dimCCD[0], _dimCCD[1]);
logDebug("CCD bits per pixel: {}", _bitsPerPixel);
logDebug("Number of grabber image framebuffers: {}", _imageFrameBuffNumber);
logDebug("-----------------------------------------------");
logDebug("Set initial state (IDLE, full frame, binning to 1x1) ...");
(*this)[CAMERA_ATTR_XBIN] = 1;
(*this)[CAMERA_ATTR_YBIN] = 1;
(*this)[CAMERA_ATTR_ROI_STARTX] = 0; // in CCD notation (started from 0)!!!
(*this)[CAMERA_ATTR_ROI_STARTY] = 0; // in CCD notation (started from 0)!!!
(*this)[CAMERA_ATTR_ROI_HEIGHT] = 0; // ??!!!!
(*this)[CAMERA_ATTR_ROI_WIDTH] = _dimCCD[0];
(*this)[CAMERA_ATTR_ROI_HEIGHT] = _dimCCD[1];
(*this)[CAMERA_ATTR_READ_MODE] = CAMERA_ATTR_READ_MODE_NORMAL;
(*this)[CAMERA_ATTR_READ_RATE] = CAMERA_ATTR_READ_RATE_FAST;
// IDLE mode
(*this)[CAMERA_ATTR_TRIGGER_MODE] = CAMERA_ATTR_TRIGGER_MODE_IDLE;
// clearTriggerRegisterBit(CL_TRIGGER_MODE_EXT_TRIGGER_BIT);
// clearTriggerRegisterBit(CL_TRIGGER_MODE_CONTINUOUS_SEQ_BIT);
// setTriggerRegisterBit(CL_TRIGGER_MODE_ABORT_CURRENT_EXP_BIT);
_permanentFitsKeywords.clear();
_currentFitsKeywords.clear();
// xclibApiCall<true>(pxd_eventFieldClose(_cameraUnitmap, SIGUSR2),
// std::format("pxd_eventFieldClose({}, {})", _cameraUnitmap, SIGUSR2));
// xclibApiCall(pxd_eventFieldCreate(_cameraUnitmap, SIGUSR2, NULL),
// std::format("pxd_eventFieldCreate({}, {}, NULL)", _cameraUnitmap, SIGUSR2));
// std::signal(SIGUSR2, [this](int signo) { logDebug("SIGUSR2 SIGNAL IS RECEIVED!!!");
// });
logInfo("Camera with unitmap '{}' is initialized", _cameraUnitmap);
return true;
}
void RaptorEagleCCD::openPIXCI()
{
logDebug("Initialize EPIX library and camera system device ...");
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
// #include "raptor_eagle-v.fmt" // exported from XCAP (Linux 64-bit!): bin 1x1, full CCD frame
pxd_videoFormatAsIncludedInit(0);
xclibApiCall(pxd_videoFormatAsIncluded(0), "pxd_videoFormatAsIncluded(0)");
}
}
void RaptorEagleCCD::closePIXCI()
{
logDebug("Close EPIX library and camera system device ...");
// no exception here!!!
xclibApiCall<true>(pxd_PIXCIclose(), "pxd_PIXCIclose()");
}
/* CameraLink-RELATED METHODS */
size_t RaptorEagleCCD::clRead(byte_seq_t& bytes)
{
std::lock_guard lock_guard(_camlinkMutex);
size_t nbytes;
auto start_tp = std::chrono::steady_clock::now();
// how many byte are available
xclibApiCall(nbytes = pxd_serialRead(_cameraUnitmap, 0, nullptr, 0),
std::format("pxd_serialRead({}, 0, NULL, 0)", _cameraUnitmap), spdlog::level::trace);
if (!nbytes) {
// logWarn("There are no bytes in Rx-buffer! Polling buffer during {} ...", CL_DEFAULT_TIMEOUT);
logTrace("There are no bytes in Rx-buffer! Polling buffer during {} ...", CL_DEFAULT_TIMEOUT);
while ((std::chrono::steady_clock::now() - start_tp) <= CL_DEFAULT_TIMEOUT) {
std::this_thread::sleep_for(std::chrono::milliseconds(5));
nbytes = pxd_serialRead(_cameraUnitmap, 0, nullptr, 0);
if (nbytes) {
break;
}
}
if (!nbytes) {
// logWarn("Cameralink reading operation timeout!");
// return 0;
throw std::system_error(RaptorEagleCCDError::ERROR_CAMLINK_READ_TIMEOUT);
}
// here the call is only for logging purpose
xclibApiCall(nbytes = pxd_serialRead(_cameraUnitmap, 0, nullptr, 0),
std::format("pxd_serialRead({}, 0, NULL, 0)", _cameraUnitmap), spdlog::level::trace);
}
// 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,
details::formatByteArr(bytes | std::views::take(nbytes))),
spdlog::level::trace);
// 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);
auto ack = *(bytes.begin() + nbytes - 1 - _clChecksumBit);
if (ack != CL_ETX) {
// throw std::system_error(std::error_code(ack, RaptorEagleControllerErrorCategory::get()));
throw std::system_error(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), spdlog::level::trace);
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);
return 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, details::formatByteArr(bytes),
bytes.size()),
spdlog::level::trace);
// xclibApiCall(
// nbytes = pxd_serialWrite(_cameraUnitmap, 0, (char*)bytes.data(), bytes.size()),
// std::format("pxd_serialWrite({}, 0, {}, {})", _cameraUnitmap, (void*)bytes.data(), bytes.size()));
// send trailing ETX and possible checksum bytes
if (tr_nbytes > 1) {
// logDebug("Write trailing ETX and checksum bytes");
logTrace("Write trailing ETX and checksum bytes");
} else {
// logDebug("Write trailing ETX byte");
logTrace("Write trailing ETX byte");
}
xclibApiCall(pxd_serialWrite(_cameraUnitmap, 0, (char*)etx_checksum_bytes, tr_nbytes),
std::format("pxd_serialWrite({}, 0, [{}], {})", _cameraUnitmap,
details::formatByteArr(std::string_view((const char*)etx_checksum_bytes, 2) |
std::views::take(tr_nbytes)),
tr_nbytes),
spdlog::level::trace);
// xclibApiCall(
// pxd_serialWrite(_cameraUnitmap, 0, (char*)etx_checksum_bytes, tr_nbytes),
// std::format("pxd_serialWrite({}, 0, {}, {})", _cameraUnitmap, (void*)etx_checksum_bytes, tr_nbytes));
}
} else {
logWarn("No available space in the internal Tx-buffer! Nothing to do!");
}
return bytes.size();
}
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
}
}
/* RESET HARDWARE */
bool RaptorEagleCCD::resetMicro(const std::chrono::milliseconds& timeout)
{
std::lock_guard lock_guard(_camlinkMutex);
std::chrono::milliseconds tm = timeout;
if (tm < MICRO_RESET_TIME_CONSTANT) { // must be greater than ~100ms
logWarn("Microcontroller reset timeout must be greater than {}", MICRO_RESET_TIME_CONSTANT);
logWarn("Use of default value {}", MICRO_RESET_DEFAULT_TIMEOUT);
tm = std::chrono::milliseconds(MICRO_RESET_DEFAULT_TIMEOUT);
}
byte_seq_t ack(1);
std::chrono::milliseconds::rep cnt = (tm - MICRO_RESET_TIME_CONSTANT).count();
std::chrono::milliseconds sleep_dur =
cnt > 10 ? std::chrono::milliseconds(cnt / 10) : std::chrono::milliseconds(10);
uint8_t cksum_old = _clChecksumBit;
_clChecksumBit = 1; // to compute mandatory checksum in clWrite below!
clWrite({0x55, 0x99, 0x66, 0x11}); // no response here
_clChecksumBit = cksum_old; // restore
// according to instruction manual rev 1.1 microcontroller will take near 100msecs to reset
std::this_thread::sleep_for(std::chrono::milliseconds(100));
// poll controller
auto start = std::chrono::steady_clock::now();
do {
// poll camera with 'set-system-status'
clWrite({0x4F, 0x51});
// clWrite({0x4F, 0x50});
std::this_thread::sleep_for(sleep_dur);
clRead(ack);
if (ack[0] == CL_ETX) {
logInfo("Camera microcontroller is reset successfully!");
return true;
}
} while ((std::chrono::steady_clock::now() - start) < timeout);
return false;
}
bool RaptorEagleCCD::resetFPGA(const std::chrono::milliseconds& timeout)
{
std::lock_guard lock_guard(_camlinkMutex);
std::chrono::milliseconds tm = timeout;
if (tm < FPGA_RESET_TIME_CONSTANT) { // must be greater than ~100ms
logWarn("FPGA reset timeout must be greater than {} millisecs", FPGA_RESET_TIME_CONSTANT.count());
logWarn("Use of default value {}", FPGA_RESET_DEFAULT_TIMEOUT);
tm = std::chrono::milliseconds(FPGA_RESET_DEFAULT_TIMEOUT);
}
byte_seq_t ack;
std::chrono::milliseconds::rep cnt = (tm - FPGA_RESET_TIME_CONSTANT).count();
std::chrono::milliseconds sleep_dur =
cnt > 10 ? std::chrono::milliseconds(cnt / 10) : std::chrono::milliseconds(10);
// clearSystemStateBit(CL_SYSTEM_STATUS_FPGA_RST_HOLD_BIT); // set bit to 0 to hold FPGA in reset state
clWrite({0x4F, 0x52});
clRead(ack); // ignore answer
std::this_thread::sleep_for(std::chrono::milliseconds(200));
clWrite({0x4F, 0x50});
clRead(ack); // ignore answer
// setSystemStateBit(CL_SYSTEM_STATUS_FPGA_RST_HOLD_BIT); // set bit to 1 to boot FPGA
clWrite({0x4F, 0x52});
clRead(ack); // ignore answer
// according to instruction manual rev 1.1 FPGA will take approximately 500msecs to reset
std::this_thread::sleep_for(std::chrono::milliseconds(500));
// poll controller
auto start = std::chrono::steady_clock::now();
do {
clWrite({0x49});
std::this_thread::sleep_for(sleep_dur);
clRead(ack);
auto bits = std::bitset<8>(ack[0]);
if (bits.test(CL_SYSTEM_STATUS_FPGA_BOOT_OK_BIT)) {
// logInfo("bits = {}", bits.to_string());
logInfo("Camera FPGA is reset successfully!");
return true;
}
} while ((std::chrono::steady_clock::now() - start) < timeout);
return false;
}
/* HARDWARE INFO */
void RaptorEagleCCD::getHardwareInfo()
{
std::lock_guard lock_guard(_camlinkMutex);
logDebug("Try to get manufacturer EPROM data ...");
// first, according to instruction manual, set FPGA comms bit
setSystemStateBit(CL_SYSTEM_STATUS_FPGA_EEPROM_COMMS_BIT);
// get manufacturer data
clWrite({0x53, 0xAE, 0x05, 0x01, 0x00, 0x00, 0x02, 0x00});
clReadAndCheckAck();
clWrite({0x53, 0xAF, 0x12});
clReadAndCheckAck(_manufacturerData);
_buildDate =
std::chrono::year_month_day(std::chrono::year(2000 + _manufacturerData[4]) /
std::chrono::month(_manufacturerData[3]) / std::chrono::day(_manufacturerData[2]));
logDebug("------- Manufacturer data -------");
logDebug("Camerial serial number: {}", _cameraSerialNumber);
logDebug("Build date: {}", _buildDate);
logDebug("Build code: {}", _buildCode);
// ADC calibration data
double cnt1 = *reinterpret_cast<uint16_t*>(_manufacturerData.data() + 10); // at 0C
double cnt2 = *reinterpret_cast<uint16_t*>(_manufacturerData.data() + 12); // at +40C
logDebug("");
logDebug("ADC calib data [{}, {}] counts at [{}C, {}C]", _adcCCDTempCalibData[0], _adcCCDTempCalibData[1],
ADC_CALIBRATION_POINT_1, ADC_CALIBRATION_POINT_2);
// compute linear relation: Temp = k*ADC + b
_adcCCDTempCalibCoeffs[0] = (ADC_CALIBRATION_POINT_2 - ADC_CALIBRATION_POINT_1) / (cnt2 - cnt1); // k
_adcCCDTempCalibCoeffs[1] = ADC_CALIBRATION_POINT_2 - _adcCCDTempCalibCoeffs[0] * cnt2;
logDebug("Computed ADC-to-Temp linear relation: Temp(C) = {:7.4f}*ADC(counts) + {:6.2f}", _adcCCDTempCalibCoeffs[0],
_adcCCDTempCalibCoeffs[1]);
logDebug("");
logDebug("DAC calib data [{}, {}] counts at [{}C, {}C]", _dacTECSetPointCalibData[0], _dacTECSetPointCalibData[1],
DAC_CALIBRATION_POINT_1, DAC_CALIBRATION_POINT_2);
cnt1 = *reinterpret_cast<uint16_t*>(_manufacturerData.data() + 14); // at 0C
cnt2 = *reinterpret_cast<uint16_t*>(_manufacturerData.data() + 16); // at +40C
_dacTECSetPointCalibCoeffs[0] = (DAC_CALIBRATION_POINT_2 - DAC_CALIBRATION_POINT_1) / (cnt2 - cnt1);
_dacTECSetPointCalibCoeffs[1] = DAC_CALIBRATION_POINT_2 - _dacTECSetPointCalibCoeffs[0] * cnt2;
if (_dacTECSetPointCalibCoeffs[1] > 0.0) {
logDebug("Computed DAC-to-Temp linear relation: Temp(C) = {:7.4f}*DAC(counts) + {:6.2f}",
_dacTECSetPointCalibCoeffs[0], _dacTECSetPointCalibCoeffs[1]);
} else {
logDebug("Computed DAC-to-Temp linear relation: Temp(C) = {:7.4f}*DAC(counts) - {:6.2f}",
_dacTECSetPointCalibCoeffs[0], std::abs(_dacTECSetPointCalibCoeffs[1]));
}
_dacTECSetPointCalibCoeffs[2] = (cnt2 - cnt1) / (DAC_CALIBRATION_POINT_2 - DAC_CALIBRATION_POINT_1);
_dacTECSetPointCalibCoeffs[3] = cnt2 - _dacTECSetPointCalibCoeffs[2] * DAC_CALIBRATION_POINT_2;
logDebug("Computed Temp-to-Dac linear relation: DAC(counts) = {}*Temp(C) + {}", _dacTECSetPointCalibCoeffs[2],
_dacTECSetPointCalibCoeffs[3]);
logDebug("---------------------------------");
clearSystemStateBit(CL_SYSTEM_STATUS_FPGA_EEPROM_COMMS_BIT);
}
void RaptorEagleCCD::getMicroVersion()
{
std::lock_guard lock_guard(_camlinkMutex);
logDebug("Try to get microcontroller version ...");
clWrite({0x56});
clReadAndCheckAck(_microVersion);
logDebug("Microcontroller version: {}.{}", _microVersion[0], _microVersion[1]);
}
void RaptorEagleCCD::getFPGAVersion()
{
std::lock_guard lock_guard(_camlinkMutex);
logDebug("Try to get FPGA version ...");
_FPGAVersion = readRegisters({0x7E, 0x7F});
logDebug("FPGA version: {}.{}", _FPGAVersion[0], _FPGAVersion[1]);
}
/* ACQUISITION PROCESS */
void RaptorEagleCCD::startAquisition()
{
if (AcquisitionProcess::isAcqInProgress) {
logError("Acquisition is in progress! Exit!");
throw std::system_error(RaptorEagleCCDError::ERROR_ACQUISITION_IN_PROGRESS);
}
// auto bytes = readRegisters({0xD4}); // trigger mode register
// std::bitset<8> bits(bytes[0]);
auto bits = getTriggerRegister();
if (bits.test(CL_TRIGGER_MODE_EXT_TRIGGER_BIT)) {
logError("External trigger mode is set! Nothing to do, exit!");
throw std::system_error(RaptorEagleCCDError::ERROR_EXT_TRIGGER_MODE);
}
std::lock_guard lock_guard(_acqProcessesMutex);
if (_acqRingFreeBufferPtrs.empty()) {
logDebug("There is no free image buffers! Try to shrink ring buffer ...");
if (_acqRingBuffer.size() < DEFAULT_ACQ_RING_BUFFER_MAX_SIZE) { // shrink
size_t N = 0;
for (auto i = _acqRingBuffer.size(); i < DEFAULT_ACQ_RING_BUFFER_MAX_SIZE; ++i, ++N) {
if (N == DEFAULT_ACQ_RING_BUFFER_SIZE) {
break;
}
_acqRingBuffer.emplace_back(new ushort[_dimCCD[0] * _dimCCD[1]]);
_acqRingFreeBufferPtrs.push(_acqRingBuffer.back().get());
}
logDebug("{} new image buffers were allocated", N);
} else {
logError("Ring buffer exceeded maximum size!");
throw std::system_error(RaptorEagleCCDError::ERROR_NO_FREE_BUFFER);
}
}
// check filesystem permissions
std::string fname = (*this)[CAMERA_ATTR_FITS_FILENAME];
std::error_code ec;
std::filesystem::path pt(fname);
if (pt.filename().empty()) {
fname = "";
} else {
auto pt_p = pt.parent_path();
if (pt_p.empty()) {
pt_p = ".";
}
auto pt_cn = std::filesystem::canonical(pt_p, ec);
if (ec) {
logError("Invalid FITS-image filename path: {}", pt.c_str());
throw std::system_error(RaptorEagleCCDError::ERROR_INVALID_PATH);
}
// still only for POSIX OSes
int res = access(pt_cn.c_str(), W_OK | X_OK);
if (res == -1) {
logError("Invalid FITS-image path! Insufficient filesystem permissions!");
throw std::system_error(RaptorEagleCCDError::ERROR_INSUFFICIENT_FILESYSTEM_PERMISSIONS);
}
fname = pt_cn / pt.filename(); // use canonical file path
}
logInfo("Start acquisition process ...");
auto acq_pars = std::make_shared<acq_params_t>(
acq_params_t({.startTime = std::chrono::utc_clock::time_point(),
.abortTime = std::chrono::utc_clock::time_point(),
.saveInAbort = false,
.expTime = (*this)[CAMERA_ATTR_EXPTIME],
.roiStartX = (*this)[CAMERA_ATTR_ROI_STARTX], // in CCD pixels (start from 0)
.roiStartY = (*this)[CAMERA_ATTR_ROI_STARTY], // in CCD pixels (start from 0)
.roiWidth = (*this)[CAMERA_ATTR_ROI_WIDTH], // in binned pixels
.roiHeight = (*this)[CAMERA_ATTR_ROI_HEIGHT], // in binned pixels
.binX = (*this)[CAMERA_ATTR_XBIN],
.binY = (*this)[CAMERA_ATTR_YBIN],
.shutterState = (*this)[CAMERA_ATTR_SHUTTER_STATE],
.readRate = (*this)[CAMERA_ATTR_READ_RATE],
.readMode = (*this)[CAMERA_ATTR_READ_MODE],
.gain = (*this)[CAMERA_ATTR_GAIN],
.ccdTemp = (*this)[CAMERA_ATTR_CCD_TEMP],
.tecSetPoint = (*this)[CAMERA_ATTR_TECPOINT],
.tecState = (*this)[CAMERA_ATTR_TECSTATE] == CAMERA_ATTR_TECSTATE_ON ? true : false,
.pcbTemp = (*this)[CAMERA_ATTR_PCB_TEMP],
// .filename = (*this)[CAMERA_ATTR_FITS_FILENAME],
.filename = fname,
.templateFilename = (*this)[CAMERA_ATTR_FITS_TEMPLATE],
.permanentKeywords = _permanentFitsKeywords, // copy
.currentKeywords = std::move(_currentFitsKeywords), // move!!!
.imageBufferPtr = _acqRingFreeBufferPtrs.front()}));
_acqRingFreeBufferPtrs.pop();
// adjust geometry
auto xmax = acq_pars->roiStartX + acq_pars->roiWidth;
auto ymax = acq_pars->roiStartY + acq_pars->roiHeight;
if (xmax > _dimCCD[0]) {
acq_pars->roiWidth = _dimCCD[0] - acq_pars->roiStartX;
logDebug("Adjust ROI width to {}", acq_pars->roiWidth);
}
if (ymax > _dimCCD[1]) {
acq_pars->roiHeight = _dimCCD[1] - acq_pars->roiStartY;
logDebug("Adjust ROI height to {}", acq_pars->roiHeight);
}
// std::lock_guard lock_guard(_acqProcessesMutex);
auto sptr = std::make_shared<AcquisitionProcess>(this);
for (auto it = _acqProcesses.begin(); it != _acqProcesses.end();) {
if (it->expired()) {
it = _acqProcesses.erase(it);
} else {
break;
}
}
_acqProcesses.emplace_back(sptr);
// arm grabber here
sptr->start(acq_pars);
// start acquisition here
acq_pars->startTime = setTriggerRegisterBit(CL_TRIGGER_MODE_SNAPSHOT_BIT);
int status;
xclibApiCall(status = pxd_goneLive(_cameraUnitmap, 0), std::format("pxd_goneLive({}, 0)", _cameraUnitmap));
if (status == 0) {
logError("CANNOT START ACQUIRING!!!");
sptr->_status = AcquisitionProcess::STATUS_IDLE;
} else {
sptr->_status = AcquisitionProcess::STATUS_ACQ;
}
}
void RaptorEagleCCD::stopAcquisition(bool save_acq)
{
std::lock_guard lock_guard(_acqProcessesMutex);
for (auto it = _acqProcesses.begin(); it != _acqProcesses.end();) {
if (it->expired()) {
it = _acqProcesses.erase(it);
} else {
auto sptr = it->lock();
sptr->stop(save_acq);
return; // there was only the single active aquisition, so exit here!
}
}
logWarn("Stop acquisition is asked but there is no active one! Ignore!");
}
/* CREATE COMMANDS AND ATTRIBUTES */
void RaptorEagleCCD::initAttrComm()
{
logDebug("Try to create attributes and commands ...");
auto comp_case_ignore = [](const auto& v1, const auto& v2) { return std::toupper(v1) == v2; };
// helper to setup 8-bit register attributes
// 'validator' is a callable with signature: std::pair<uchar, std::string> validator(const uchar&)
auto create8BitAttr = [this](attr_ident_t name, auto reg_addr, auto&& validator, std::string_view log_mark) {
return RaptorEagleCCD::attribute_t::makeArithAttr(
name,
[this, reg_addr, log_mark]() {
auto bytes = readRegisters(reg_addr);
logTrace("Return {} (current value: {})", log_mark, bytes[0]);
return bytes[0];
},
[this, reg_addr, log_mark,
wrapper =
adc::traits::adc_pf_wrapper(std::forward<decltype(validator)>(validator))](const uchar& 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);
}
writeRegisters(reg_addr, {v_res.first});
logDebug("{} is set to {}", log_mark, v_res.first);
});
};
// helper to setup 12-bit register attributes
// 'validator' is a callable with signature: std::pair<uint16_t, std::string> validator(const uint16_t&)
auto create12BitAttr = [this](attr_ident_t name, auto reg_addrs, auto&& validator, std::string_view log_mark) {
return RaptorEagleCCD::attribute_t::makeArithAttr(
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);
});
};
/* ------- COMMANDS ------- */
addCommand(CAMERA_CMD_INITCAM, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_INITCAM);
initCamera();
});
addCommand(CAMERA_CMD_START_EXP, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_START_EXP);
startAquisition();
});
addCommand(CAMERA_CMD_STOP_EXP, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_STOP_EXP);
stopAcquisition(true);
});
addCommand(CAMERA_CMD_ABORT_EXP, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_ABORT_EXP);
stopAcquisition(false);
});
addCommand(CAMERA_CMD_CLEAR_PERM_KEYW, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_CLEAR_PERM_KEYW);
auto N = _permanentFitsKeywords.size();
_permanentFitsKeywords.clear();
logInfo("Permanent FITS keywords are deleted! ({} keywords were cleared)", N);
});
addCommand(CAMERA_CMD_START_RESET_MICRO, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_START_RESET_MICRO);
if (resetMicro())
return;
throw std::system_error(RaptorEagleCCDError::ERROR_CANNOT_RESET_MICRO);
});
addCommand(CAMERA_CMD_START_RESET_FPGA, [this]() {
logDebug("Try to execute '{}' command", CAMERA_CMD_START_RESET_FPGA);
if (resetFPGA())
return;
throw std::system_error(RaptorEagleCCDError::ERROR_CANNOT_RESET_FPGA);
});
/* ------- ATTRIBUTES ------- */
/* CAMERA CURRENT STATUS (READ-ONLY) */
addAttribute(CAMERA_ATTR_CAMERA_STATUS, [this]() {
std::lock_guard lock_guard(_acqProcessesMutex);
std::string s, s_head;
if (!_acqProcesses.empty()) {
for (auto it = _acqProcesses.begin(); it != _acqProcesses.end();) {
if (it->expired()) {
it = _acqProcesses.erase(it);
} else {
auto sptr = it->lock();
auto st = sptr->status();
if (st.substr(0, CAMERA_ATTR_CAMERA_STATUS_ACQ.size()) ==
CAMERA_ATTR_CAMERA_STATUS_ACQ) { // if the camera is acquiring then
s_head = st + ","; // return it at the beginning of the status string
} else if (st.substr(0, CAMERA_ATTR_CAMERA_STATUS_IDLE.size()) == CAMERA_ATTR_CAMERA_STATUS_IDLE) {
// here, cquisition process is already inactive
it = _acqProcesses.erase(it);
continue;
} else {
std::ranges::copy(st, std::back_inserter(s));
s += ",";
}
++it;
}
}
}
if (!s.empty() || !s_head.empty()) {
s = s_head + s;
// if (_acqProcesses.size() == 1) {
s.resize(s.size() - 1); // delete trailing ","
// }
} else {
s = std::string{CAMERA_ATTR_CAMERA_STATUS_IDLE.begin(), CAMERA_ATTR_CAMERA_STATUS_IDLE.end()};
}
logTrace("Return current camera status as {}", s);
return s;
});
/* CURRENT FITS IMAGE FILENAME AND ITS HEADER TEMPLATE, PERMANENT AND CURRENT USER FITS KEYWORDS */
addAttribute(
CAMERA_ATTR_FITS_FILENAME,
[this]() {
logTrace("Return current FITS-image filename as {}", _currentFitsFile);
return _currentFitsFile;
},
[this](const std::string& filename) {
logDebug("Set current FITS-image filename to {}", filename);
if (filename.empty()) {
logWarn("An empty FITS filename! Acquisition process is disabled!");
}
_currentFitsFile = filename;
});
addAttribute(
CAMERA_ATTR_FITS_TEMPLATE,
[this]() {
logTrace("Return current FITS-image header template filename as {}", _currentTemplateFile);
return _currentTemplateFile;
},
[this](const std::string& filename) {
logDebug("Set current FITS-image header template filename to {}", filename);
_currentTemplateFile = filename;
});
// NOTE: setter and deserializer adds keywords to the end of current array!!!
addAttribute(
CAMERA_ATTR_PERM_KEYW,
[this]() {
auto N = _permanentFitsKeywords.size();
logTrace("Return permanent FITS keywords ({} keys)", N);
return _permanentFitsKeywords;
},
[this](const std::vector<std::string>& keys) {
logInfo("Add permanent FITS keywords to current array ({} keys)", keys.size());
for (auto& key : keys) {
logTrace("\tadd keyword record: |{}|", key);
_permanentFitsKeywords.push_back(key);
}
},
[](const std::vector<std::string>& keys) { // serialize as "USER_FITS_KEY_SEP_SEQ" separated char sequences
attribute_t::serialized_t res;
if (keys.size() > 1) {
for (auto& key : keys) {
std::ranges::copy(key, std::back_inserter(res));
std::ranges::copy(USER_FITS_KEY_SEP_SEQ, std::back_inserter(res));
}
} else {
std::ranges::copy(keys.front(), std::back_inserter(res));
}
return res;
},
[](const attribute_t::serialized_t& char_seq) {
std::vector<std::string> keys;
for (auto const& key : char_seq | std::views::split(USER_FITS_KEY_SEP_SEQ)) {
keys.push_back({key.begin(), key.end()});
}
return keys;
});
// NOTE: setter and deserializer adds keywords to the end of current array!!!
addAttribute(
CAMERA_ATTR_CURR_KEYW,
[this]() {
auto N = _currentFitsKeywords.size();
logTrace("Return current FITS keywords ({} keys)", N);
return _currentFitsKeywords;
},
[this](const std::vector<std::string>& keys) {
logInfo("Add current FITS keywords to current array ({} keys)", keys.size());
for (auto& key : keys) {
logTrace("\tadd keyword record: |{}|", key);
_currentFitsKeywords.push_back(key);
}
},
[](const std::vector<std::string>& keys) { // serialize as "USER_FITS_KEY_SEP_SEQ" separated char sequences
attribute_t::serialized_t res;
if (keys.size() > 1) {
for (auto& key : keys) {
std::ranges::copy(key, std::back_inserter(res));
std::ranges::copy(USER_FITS_KEY_SEP_SEQ, std::back_inserter(res));
}
} else {
std::ranges::copy(keys.front(), std::back_inserter(res));
}
return res;
},
[](const attribute_t::serialized_t& char_seq) {
std::vector<std::string> keys;
for (auto const& key : char_seq | std::views::split(USER_FITS_KEY_SEP_SEQ)) {
keys.push_back({key.begin(), key.end()});
}
return keys;
});
/* EXPOSURE AND FRAMERATE */
// exposure time
addAttribute(RaptorEagleCCD::attribute_t::makeArithAttr(
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(RaptorEagleCCD::attribute_t::makeArithAttr(
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(RaptorEagleCCD::attribute_t::makeArithAttr(
CAMERA_ATTR_NEXP,
[this]() -> size_t {
logTrace("Return number of frames in acquisition sequence (current value is {})", _frameNumbers.load());
return _frameNumbers;
},
[this](const size_t& nframes) {
_frameNumbers = nframes;
logDebug("Number of frames in acquisition sequence is set to {}", _frameNumbers.load());
}));
/* FRAME GEOMETRY RELATED ATTRIBUTES */
// ROI left
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_STARTX, CL_ROI_STARTX_ADDR,
[this]<typename T>(const T& val) { // validator
std::pair<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]);
// }
if (val >= _dimCCD[0]) {
res.first = _dimCCD[0] - 1;
res.second =
std::format("The ROI X-offset must be lesser than CCD X-dimension of {} pixels", _dimCCD[0]);
}
return res;
},
"ROI X-offset"));
// ROI top
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_STARTY, CL_ROI_STARTY_ADDR,
[this]<typename T>(const T& val) { // validator
std::pair<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]);
// }
if (val >= _dimCCD[1]) {
res.first = _dimCCD[1] - 1;
res.second =
std::format("The ROI Y-offset must be lesser than CCD Y-dimension of {} pixels", _dimCCD[1]);
}
return res;
},
"ROI Y-offset"));
// ROI width
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_WIDTH, CL_ROIWIDTH_ADDR,
[this]<typename T>(const T& val) { // validator
std::pair<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", _dimCCD[0]);
}
return res;
},
"ROI width"));
// ROI height
addAttribute(create12BitAttr(
CAMERA_ATTR_ROI_HEIGHT, CL_ROIHEIGHT_ADDR,
[this]<typename T>(const T& val) { // validator
std::pair<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", _dimCCD[1]);
}
return res;
},
"ROI height"));
// binning validator (1-32, 64)
auto bin_validator = []<typename T>(const T& val, std::string_view log_name) {
std::pair<T, std::string> res{val, ""};
T* limits = (T*)EAGLE_CAMERA_MAX_XBIN;
if (log_name == "YBIN") {
limits = (T*)EAGLE_CAMERA_MAX_YBIN;
}
if (val < 1) {
res.first = 1;
res.second = std::format("The {} must start from 1", log_name);
} else if ((val > limits[0]) && (val < limits[1])) {
// set to the closest
res.first = (val - limits[0]) < (limits[1] - val) ? limits[0] : limits[1];
res.second = std::format("The {} must not be within {} and {}", log_name, limits[0], limits[1]);
} else if (val > limits[1]) {
res.first = limits[1];
res.second = std::format("The {} must not be greater than {}", log_name, limits[1]);
}
return res;
};
// X-bin
addAttribute(attribute_t::makeArithAttr(
CAMERA_ATTR_XBIN,
[this]() {
auto bytes = readRegisters(CL_XBIN_ADDR);
// inner register value of binning starts from 0!!!
logDebug("Return XBIN as {} (inner register value: {})", bytes[0] + 1, bytes[0]);
return bytes[0] + 1;
},
[&bin_validator, this](const uchar& val) {
logDebug("Try to set XBIN to {} ...", val);
auto v_res = bin_validator(val, "XBIN");
if (v_res.second.size()) {
logWarn(v_res.second);
}
// inner register value of binning starts from 0!!!
v_res.first -= 1;
writeRegisters(CL_XBIN_ADDR, {v_res.first});
logDebug("XBIN is set to {} (inner register value {})", v_res.first + 1, v_res.first);
}));
// Y-bin
addAttribute(attribute_t::makeArithAttr(
CAMERA_ATTR_YBIN,
[this]() {
auto bytes = readRegisters(CL_YBIN_ADDR);
// inner register value of binning starts from 0!!!
logDebug("Return YBIN as {} (inner register value: {})", bytes[0] + 1, bytes[0]);
return bytes[0] + 1;
},
[&bin_validator, this](const uchar& val) {
logDebug("Try to set YBIN to {} ...", val);
auto v_res = bin_validator(val, "YBIN");
if (v_res.second.size()) {
logWarn(v_res.second);
}
// inner register value of binning starts from 0!!!
v_res.first -= 1;
writeRegisters(CL_YBIN_ADDR, {v_res.first});
logDebug("YBIN is set to {} (inner register value {})", v_res.first + 1, v_res.first);
}));
/* TEC SET POINT AND STATE */
// DAC counts
addAttribute(create12BitAttr(
CAMERA_ATTR_TECPOINT_DAC, CL_TECPOINT_ADDR,
[]<typename T>(const T& counts) {
std::pair<T, std::string> res{counts, ""};
if (counts > 0x0FFF) {
res.second =
std::format("TEC set point counts must not be greater than {}. Set it to {}!", 0x0FFF, 0x0FFF);
res.first = 0x0FFF;
}
return res;
},
"TEC set point"));
// floating-point value
addAttribute(RaptorEagleCCD::attribute_t::makeArithAttr(
CAMERA_ATTR_TECPOINT,
[this]() {
double counts = (*this)[CAMERA_ATTR_TECPOINT_DAC];
double temp = _dacTECSetPointCalibCoeffs[0] * counts + _dacTECSetPointCalibCoeffs[1];
logDebug("Return TEC set point as {} Celsius degrees", temp);
return temp;
},
[this](const double& temp) {
uint64_t v = static_cast<uint64_t>(temp * _dacTECSetPointCalibCoeffs[2] + _dacTECSetPointCalibCoeffs[3]);
uint16_t counts = v & 0x0FFF; // extract 12-bits
logInfo("Set TEC setup point to {} C", temp);
(*this)[CAMERA_ATTR_TECPOINT_DAC] = counts;
}));
addAttribute(
CAMERA_ATTR_TECSTATE,
[this]() {
bool bit = getFPGAState().test(CL_FPGA_CTRL_REG_ENABLE_TEC_BIT);
if (bit) {
return CAMERA_ATTR_TECSTATE_ON;
} else {
return CAMERA_ATTR_TECSTATE_OFF;
}
},
[this](const std::string_view& state) {
if (state == CAMERA_ATTR_TECSTATE_ON) {
logInfo("Turn ON TEC");
setFPGAStateBit(CL_FPGA_CTRL_REG_ENABLE_TEC_BIT);
} else if (state == CAMERA_ATTR_TECSTATE_OFF) {
logInfo("Turn OFF TEC");
clearFPGAStateBit(CL_FPGA_CTRL_REG_ENABLE_TEC_BIT);
} else {
logWarn("Invalid TEC state string value! Ignore!");
}
},
adc::utils::AdcDefaultValueConverter<>::serialize<attribute_t::serialized_t, std::string_view>,
[&comp_case_ignore](const attribute_t::serialized_t& v) {
if (std::ranges::equal(v, CAMERA_ATTR_TECSTATE_ON, comp_case_ignore)) {
return CAMERA_ATTR_TECSTATE_ON;
} else if (std::ranges::equal(v, CAMERA_ATTR_TECSTATE_OFF, comp_case_ignore)) {
return CAMERA_ATTR_TECSTATE_OFF;
}
return CAMERA_ATTR_STR_INVALID;
});
/* CCD and PCB temperature (read-only) */
addAttribute(RaptorEagleCCD::attribute_t::makeArithAttr(CAMERA_ATTR_PCB_TEMP, [this]() {
uint16_t bits = 0x0FFF;
double val = -1000; // impossible value
try {
// unusual set-address command (extra 0x00 byte after the address)!
auto bytes = readRegisters({0x70, 0x71}, {0x53, 0xE0, 0x02, 0x00, 0x00});
bits = details::convert12BitToUInt(bytes);
val = bits / 16.0;
} catch (const std::system_error& ex) {
logError("An error occured while trying to get PCB temperature! (code = {}, category = {}, msg = {})",
ex.code().value(), ex.code().category().name(), ex.code().message());
}
logTrace("Return PCB temperature (current value: {}; bits: {})", val, bits);
return val;
}));
addAttribute(RaptorEagleCCD::attribute_t::makeArithAttr(CAMERA_ATTR_CCD_TEMP, [this]() {
uint16_t bits = 0xFFFF;
double val = -1000; // impossible value
try {
// unusual set-address command (extra 0x00 byte after the address)!
auto bytes = readRegisters({0x6E, 0x6F}, {0x53, 0xE0, 0x02, 0x00, 0x00});
bits = (bytes[0] << 8) + bytes[1];
val = _adcCCDTempCalibCoeffs[0] * bits + _adcCCDTempCalibCoeffs[1];
} catch (const std::system_error& ex) {
logError("An error occured while trying to get CCD temperature! (code = {}, category = {}, msg = {})",
ex.code().value(), ex.code().category().name(), ex.code().message());
}
logTrace("Return CCD temperature (current value: {}; bits: {})", val, bits);
return val;
}));
/* READ-OUT MODE (std::string_view "NORMAL" or "TEST") */
addAttribute(
CAMERA_ATTR_READ_MODE,
[this]() {
auto bytes = readRegisters(CL_READMODE_ADDR);
std::string_view val = CAMERA_ATTR_READ_MODE_NORMAL;
if (bytes[0] == CL_READOUT_MODE_NORMAL) {
} else if (bytes[0] == CL_READOUT_MODE_TEST) {
val = CAMERA_ATTR_READ_MODE_TEST;
} else {
logError("Invalid bits in readout mode register! (reg = 0x{:02X})", bytes[0]);
val = CAMERA_ATTR_STR_INVALID;
}
logTrace("Return readout mode as '{}' string", val);
return val;
},
[this](const std::string_view& mode) {
uchar bits;
if (mode == CAMERA_ATTR_READ_MODE_NORMAL) {
bits = CL_READOUT_MODE_NORMAL;
logInfo("Readout mode is set to {}", mode);
} else if (mode == CAMERA_ATTR_READ_MODE_TEST) {
bits = CL_READOUT_MODE_TEST;
logInfo("Readout mode is set to {}", mode);
} else {
logWarn("Invalid '{}' string for readout mode! Use of '{}'!", mode, CAMERA_ATTR_READ_MODE_NORMAL);
bits = CL_READOUT_MODE_NORMAL;
logInfo("Readout mode is set to {}", CAMERA_ATTR_READ_MODE_NORMAL);
}
writeRegisters(CL_READMODE_ADDR, {bits});
logDebug("Readout mode is set to 0x{:02X} bits", bits);
},
adc::utils::AdcDefaultValueConverter<>::serialize<attribute_t::serialized_t, std::string_view>,
[&comp_case_ignore](const attribute_t::serialized_t& v) {
if (std::ranges::equal(v, CAMERA_ATTR_READ_MODE_NORMAL, comp_case_ignore)) {
return CAMERA_ATTR_READ_MODE_NORMAL;
} else if (std::ranges::equal(v, CAMERA_ATTR_READ_MODE_TEST, comp_case_ignore)) {
return CAMERA_ATTR_READ_MODE_TEST;
}
return CAMERA_ATTR_STR_INVALID;
});
/* READOUT RATE (std::string_view "FAST" or "SLOW") */
addAttribute(
CAMERA_ATTR_READ_RATE,
[this]() {
auto bytes = readRegisters(CL_READOUT_CLOCK_RATE_ADDR);
std::string_view val;
if ((bytes[0] == CL_READOUT_CLOCK_RATE_A3_2MHZ) && (bytes[1] == CL_READOUT_CLOCK_RATE_A4_2MHZ)) {
val = CAMERA_ATTR_READ_RATE_FAST;
} else if ((bytes[0] == CL_READOUT_CLOCK_RATE_A3_75KHZ) && (bytes[1] == CL_READOUT_CLOCK_RATE_A4_75KHZ)) {
val = CAMERA_ATTR_READ_RATE_SLOW;
} else {
logError("Invalid bits in readout rate registers! (A3 = 0x{:02X}, A4 = 0x{:02X})", bytes[0], bytes[1]);
val = CAMERA_ATTR_STR_INVALID;
}
logTrace("Return readout rate as '{}' string", val);
return val;
},
[this](const std::string_view& rate) {
byte_seq_t bytes({CL_READOUT_CLOCK_RATE_A3_2MHZ, CL_READOUT_CLOCK_RATE_A4_2MHZ});
if (rate == CAMERA_ATTR_READ_RATE_FAST) {
logInfo("Set readout rate to {}", rate);
} else if (rate == CAMERA_ATTR_READ_RATE_SLOW) {
bytes[0] = CL_READOUT_CLOCK_RATE_A3_75KHZ;
bytes[1] = CL_READOUT_CLOCK_RATE_A4_75KHZ;
logInfo("Set readout rate to {}", rate);
} else {
logWarn("Invalid '{}' string for readout rate! Use of '{}'!", rate, CAMERA_ATTR_READ_RATE_FAST);
logInfo("Set readout rate to {}", CAMERA_ATTR_READ_RATE_FAST);
}
writeRegisters(CL_READOUT_CLOCK_RATE_ADDR, bytes);
logDebug("Readout rate is set to [0x{:02X}, 0x{:02X}] bytes", bytes[0], bytes[1]);
},
adc::utils::AdcDefaultValueConverter<>::serialize<attribute_t::serialized_t, std::string_view>,
[&comp_case_ignore](const attribute_t::serialized_t& v) {
if (std::ranges::equal(v, CAMERA_ATTR_READ_RATE_FAST, comp_case_ignore)) {
return CAMERA_ATTR_READ_RATE_FAST;
} else if (std::ranges::equal(v, CAMERA_ATTR_READ_RATE_SLOW, comp_case_ignore)) {
return CAMERA_ATTR_READ_RATE_SLOW;
}
return CAMERA_ATTR_STR_INVALID;
});
/* SHUTTER CONTROL (std::string_view "OPEN", "CLOSED", "EXP") AND OPEN/CLOSE DELAY */
addAttribute(
CAMERA_ATTR_SHUTTER_STATE,
[this]() {
auto bytes = readRegisters(CL_SHUTTER_CONTROL_ADDR);
std::string_view val;
if (bytes[0] == CL_SHUTTER_CLOSED) {
val = CAMERA_ATTR_SHUTTER_STATE_CLOSED;
} else if (bytes[0] == CL_SHUTTER_OPEN) {
val = CAMERA_ATTR_SHUTTER_STATE_OPEN;
} else if (bytes[0] == CL_SHUTTER_EXP) {
val = CAMERA_ATTR_SHUTTER_STATE_EXP;
} else {
logError("Invalid bits in shhutter control register! (reg = 0x{:02X})", bytes[0]);
val = CAMERA_ATTR_STR_INVALID;
}
logTrace("Return shutter state as '{}' string (bits = 0x{:02X})", val, bytes[0]);
return val;
},
[this](const std::string_view& state) {
byte_seq_t bytes{CL_SHUTTER_EXP};
if (state == CAMERA_ATTR_SHUTTER_STATE_EXP) {
logInfo("Set shutter state to {}", state);
} else if (state == CAMERA_ATTR_SHUTTER_STATE_CLOSED) {
bytes[0] = CL_SHUTTER_CLOSED;
logInfo("Set shutter state to {}", state);
} else if (state == CAMERA_ATTR_SHUTTER_STATE_OPEN) {
bytes[0] = CL_SHUTTER_OPEN;
logInfo("Set shutter state to {}", state);
} else {
logWarn("Invalid '{}' string for shutter state! Use of '{}'!", state, CL_SHUTTER_EXP);
logInfo("Set shutter state to {}", CL_SHUTTER_EXP);
}
writeRegisters(CL_SHUTTER_CONTROL_ADDR, bytes);
logDebug("Shutter state is set to 0x{:02X}", bytes[0]);
},
adc::utils::AdcDefaultValueConverter<>::serialize<attribute_t::serialized_t, std::string_view>,
[&comp_case_ignore](const attribute_t::serialized_t& v) {
if (std::ranges::equal(v, CAMERA_ATTR_SHUTTER_STATE_EXP, comp_case_ignore)) {
return CAMERA_ATTR_SHUTTER_STATE_EXP;
} else if (std::ranges::equal(v, CAMERA_ATTR_SHUTTER_STATE_CLOSED, comp_case_ignore)) {
return CAMERA_ATTR_SHUTTER_STATE_CLOSED;
} else if (std::ranges::equal(v, CAMERA_ATTR_SHUTTER_STATE_OPEN, comp_case_ignore)) {
return CAMERA_ATTR_SHUTTER_STATE_OPEN;
}
return CAMERA_ATTR_STR_INVALID;
});
// floating-point, value is expected in millisecs
addAttribute(RaptorEagleCCD::attribute_t::makeArithAttr(
CAMERA_ATTR_SHUTTER_CLOSEDELAY,
[this]() {
auto bytes = readRegisters({0xA7});
double delay = SHUTTER_DELAY_PERIOD * bytes[0];
logTrace("Return shutter closed delay duration as {} milliseconds", delay);
return delay;
},
[this](const double& delay) {
double d = SHUTTER_DEFAULT_DELAY_PERIOD;
if (delay < 0) {
logWarn("Shutter closed delay dration must be a non-negatve value! Use of default value {}",
SHUTTER_DEFAULT_DELAY_PERIOD);
} else if (delay > SHUTTER_MAX_DELAY_PERIOD) {
logWarn("Shutter closed delay dration must not be greater than {} value! Use of default value {}",
SHUTTER_MAX_DELAY_PERIOD, SHUTTER_DEFAULT_DELAY_PERIOD);
} else {
d = delay;
}
uchar counts = static_cast<uchar>(std::round(d / SHUTTER_DELAY_PERIOD));
writeRegisters({0xA7}, {counts});
logInfo("Shutter closed delay is set to {} msecs", d);
logDebug("Shutter closed delay bits are set to 0x{:02X}", counts);
}));
// floating-point, value is expected in millisecs
addAttribute(RaptorEagleCCD::attribute_t::makeArithAttr(
CAMERA_ATTR_SHUTTER_OPENDELAY,
[this]() {
auto bytes = readRegisters({0xA6});
double delay = SHUTTER_DELAY_PERIOD * bytes[0];
logTrace("Return shutter open delay duration as {} milliseconds", delay);
return delay;
},
[this](const double& delay) {
double d = SHUTTER_DEFAULT_DELAY_PERIOD;
if (delay < 0) {
logWarn("Shutter open delay dration must be a non-negatve value! Use of default value {}",
SHUTTER_DEFAULT_DELAY_PERIOD);
} else if (delay > SHUTTER_MAX_DELAY_PERIOD) {
logWarn("Shutter open delay dration must not be greater than {} value! Use of default value {}",
SHUTTER_MAX_DELAY_PERIOD, SHUTTER_DEFAULT_DELAY_PERIOD);
} else {
d = delay;
}
uchar counts = static_cast<uchar>(std::round(d / SHUTTER_DELAY_PERIOD));
writeRegisters({0xA6}, {counts});
logInfo("Shutter open delay is set to {} msecs", d);
logDebug("Shutter open delay bits are set to 0x{:02X}", counts);
}));
/* TRIGGER MODE */
addAttribute(
CAMERA_ATTR_TRIGGER_MODE,
[this]() {
// auto bytes = readRegisters({0xD4});
// std::bitset<8> bits{bytes[0]};
auto bits = getTriggerRegister();
std::string_view trigger_mode;
if (bits.test(CL_TRIGGER_MODE_EXT_TRIGGER_BIT)) { // external trigger enabled, what is the edge?
if (bits.test(CL_TRIGGER_MODE_ENABLE_RISING_EDGE_BIT)) {
trigger_mode = CAMERA_ATTR_TRIGGER_MODE_EXT_RISING;
} else {
trigger_mode = CAMERA_ATTR_TRIGGER_MODE_EXT_FALLING;
}
} else if (bits.test(CL_TRIGGER_MODE_CONTINUOUS_SEQ_BIT)) { // continuous sequence enabled
if (bits.test(CL_TRIGGER_MODE_FIXED_FRAME_RATE_BIT)) {
trigger_mode = CAMERA_ATTR_TRIGGER_MODE_FFR;
} else {
trigger_mode = CAMERA_ATTR_TRIGGER_MODE_ITR;
}
} else {
trigger_mode = CAMERA_ATTR_TRIGGER_MODE_SNAPSHOT;
}
// logTrace("Return trigger mode as '{}' string (bits = 0b{:08b})", trigger_mode, bytes[0]);
logTrace("Return trigger mode as '{}' string (bits = 0b{})", trigger_mode, bits.to_string());
return trigger_mode;
},
[this](const std::string_view& mode) {
uchar bits = CL_TRIGGER_MODE_IDLE;
if (mode == CAMERA_ATTR_TRIGGER_MODE_EXT_RISING) {
bits = CL_TRIGGER_MODE_EXT_RISING_EDGE;
logInfo("Trigger mode is set to {}", mode);
} else if (mode == CAMERA_ATTR_TRIGGER_MODE_EXT_FALLING) {
bits = CL_TRIGGER_MODE_EXT_FALLING_EDGE;
logInfo("Trigger mode is set to {}", mode);
} else if (mode == CAMERA_ATTR_TRIGGER_MODE_FFR) {
bits = CL_TRIGGER_MODE_FFR;
logInfo("Trigger mode is set to {}", mode);
} else if (mode == CAMERA_ATTR_TRIGGER_MODE_ITR) {
bits = CL_TRIGGER_MODE_ITR;
logInfo("Trigger mode is set to {}", mode);
} else if (mode == CAMERA_ATTR_TRIGGER_MODE_IDLE) {
logInfo("Trigger mode is set to {}", mode);
} else {
logWarn("Invalid trigger mode! Set it to {}!", CAMERA_ATTR_TRIGGER_MODE_IDLE);
}
// // snapshot mode is self-clearing bit so activate it directly in 'startAcquision' method
// if (mode != CAMERA_ATTR_TRIGGER_MODE_SNAPSHOT) {
// writeRegisters({0xD4}, {bits});
// }
// logDebug("Trigger mode bits are set to 0b{:08b}", bits);
setTriggerRegister(bits);
},
adc::utils::AdcDefaultValueConverter<>::serialize<attribute_t::serialized_t, std::string_view>,
[&comp_case_ignore](const attribute_t::serialized_t& v) {
if (std::ranges::equal(v, CAMERA_ATTR_TRIGGER_MODE_EXT_RISING, comp_case_ignore)) {
return CAMERA_ATTR_TRIGGER_MODE_EXT_RISING;
} else if (std::ranges::equal(v, CAMERA_ATTR_TRIGGER_MODE_EXT_FALLING, comp_case_ignore)) {
return CAMERA_ATTR_TRIGGER_MODE_EXT_FALLING;
} else if (std::ranges::equal(v, CAMERA_ATTR_TRIGGER_MODE_FFR, comp_case_ignore)) {
return CAMERA_ATTR_TRIGGER_MODE_FFR;
} else if (std::ranges::equal(v, CAMERA_ATTR_TRIGGER_MODE_ITR, comp_case_ignore)) {
return CAMERA_ATTR_TRIGGER_MODE_ITR;
} else if (std::ranges::equal(v, CAMERA_ATTR_TRIGGER_MODE_SNAPSHOT, comp_case_ignore)) {
return CAMERA_ATTR_TRIGGER_MODE_SNAPSHOT;
}
return CAMERA_ATTR_STR_INVALID;
});
addAttribute(
CAMERA_ATTR_GAIN,
[this]() {
auto bits = getFPGAState();
if (bits.test(CL_FPGA_CTRL_REG_HIGH_GAIN_BIT)) {
return CAMERA_ATTR_GAIN_HIGH;
} else {
return CAMERA_ATTR_GAIN_LOW;
}
},
[this](const std::string_view& gain) {
if (gain == CAMERA_ATTR_GAIN_HIGH) {
setFPGAStateBit(CL_FPGA_CTRL_REG_HIGH_GAIN_BIT);
} else if (gain == CAMERA_ATTR_GAIN_LOW) {
clearFPGAStateBit(CL_FPGA_CTRL_REG_HIGH_GAIN_BIT);
} else {
logWarn("Invalid gain mode! Set it to {}", CL_FPGA_CTRL_REG_HIGH_GAIN_BIT);
setFPGAStateBit(CL_FPGA_CTRL_REG_HIGH_GAIN_BIT);
}
},
adc::utils::AdcDefaultValueConverter<>::serialize<attribute_t::serialized_t, std::string_view>,
[&comp_case_ignore](const attribute_t::serialized_t& v) {
if (std::ranges::equal(v, CAMERA_ATTR_GAIN_HIGH, comp_case_ignore)) {
return CAMERA_ATTR_GAIN_HIGH;
} else if (std::ranges::equal(v, CAMERA_ATTR_GAIN_LOW, comp_case_ignore)) {
return CAMERA_ATTR_GAIN_LOW;
}
return CAMERA_ATTR_STR_INVALID;
});
logDebug("Attributes and commands are successfully created!");
}