From 97eb1fb2fade76f6df7de1ea400df18e9c9ad4a8 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 23 Feb 2024 13:45:11 -0500 Subject: [PATCH 01/36] Initial efforts to support General Standards Corporation 16AIO168 drivers. --- CMakeLists.txt | 1 + src/CMakeLists.txt | 15 ++ src/gsc_aio168_driver.cpp | 418 ++++++++++++++++++++++++++++++++++++++ 3 files changed, 434 insertions(+) create mode 100644 src/gsc_aio168_driver.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 97c182d38..159565669 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,6 +70,7 @@ find_package(Threads REQUIRED) find_package(GSL REQUIRED) #Some libraries are harder to find as package, so this solves that find_library(nidaqmx NAMES libnidaqmx.so) +find_library(16aio168 NAMES lib16aio168_api.so) #Handle QT and boost libraries shenanigans set(CMAKE_AUTOMOC ON) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 5e487348e..4a9bb2a69 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -159,6 +159,21 @@ target_include_directories(rtxinidaqdriver target_link_libraries(rtxinidaqdriver PRIVATE nidaqmx rtxipal) endif() +if(16aio168) +message("General Standards Corporation 16aio168 Driver API found") +add_library(rtxi_gsc16aio168_driver MODULE + gsc_aio168_driver.cpp +) + +target_include_directories(rtxi_gsc16aio168_driver + PUBLIC + "$" + "$" +) + +target_link_libraries(rtxi_gsc16aio168_driver PRIVATE 16aio168 rtxipal) +endif() + target_compile_features(rtxi PUBLIC cxx_std_17) target_compile_features(rtxipal PUBLIC cxx_std_17) target_compile_features(rtxififo PUBLIC cxx_std_17) diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp new file mode 100644 index 000000000..3dba6ff8b --- /dev/null +++ b/src/gsc_aio168_driver.cpp @@ -0,0 +1,418 @@ + +#include +#include + +#include "daq.hpp" + +constexpr std::string_view DEFAULT_DRIVER_NAME = "General Standards"; + +namespace +{ + +inline std::vector split_string(const std::string& buffer, + const std::string& delim) +{ + if (buffer.empty()) { + return {}; + } + size_t pos_start = 0; + size_t pos_end = buffer.find(delim, pos_start); + if (pos_end == std::string::npos) { + return {buffer}; + } + std::string token; + std::vector split_tokens; + const size_t delim_len = delim.size(); + while (true) { + token = buffer.substr(pos_start, pos_end - pos_start); + pos_start = pos_end + delim_len; + split_tokens.push_back(token); + pos_end = buffer.find(delim, pos_start); + if (pos_end == std::string::npos) { + break; + } + } + token = buffer.substr(pos_start, buffer.size() - pos_start); + split_tokens.push_back(token); + return split_tokens; +} + +class Device final : public DAQ::Device +{ +public: + Device(const Device&) = default; + Device(Device&&) = delete; + Device& operator=(const Device&) = delete; + Device& operator=(Device&&) = delete; + Device(const std::string& dev_name, + const std::vector& channels, + int device_file_descriptor); + ~Device() final; + + size_t getChannelCount(DAQ::ChannelType::type_t type) const final; + bool getChannelActive(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + int setChannelActive(DAQ::ChannelType::type_t type, + DAQ::index_t index, + bool state) final; + size_t getAnalogRangeCount(DAQ::index_t index) const final; + size_t getAnalogReferenceCount(DAQ::index_t index) const final; + size_t getAnalogUnitsCount(DAQ::index_t index) const final; + size_t getAnalogDownsample(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + std::string getAnalogRangeString(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t range) const final; + std::string getAnalogReferenceString(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t reference) const final; + std::string getAnalogUnitsString(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t units) const final; + double getAnalogGain(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + double getAnalogZeroOffset(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + DAQ::index_t getAnalogRange(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + DAQ::index_t getAnalogReference(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + DAQ::index_t getAnalogUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + DAQ::index_t getAnalogOffsetUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + int setAnalogGain(DAQ::ChannelType::type_t type, + DAQ::index_t index, + double gain) final; + int setAnalogRange(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t range) final; + int setAnalogZeroOffset(DAQ::ChannelType::type_t type, + DAQ::index_t index, + double offset) final; + int setAnalogReference(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t reference) final; + int setAnalogUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t units) final; + int setAnalogOffsetUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t units) final; + int setAnalogDownsample(DAQ::ChannelType::type_t type, + DAQ::index_t index, + size_t downsample) final; + int setAnalogCounter(DAQ::ChannelType::type_t type, DAQ::index_t index) final; + int setAnalogCalibrationValue(DAQ::ChannelType::type_t type, + DAQ::index_t index, + double value) final; + double getAnalogCalibrationValue(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + int setAnalogCalibrationActive(DAQ::ChannelType::type_t type, + DAQ::index_t index, + bool state) final; + bool getAnalogCalibrationActive(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + bool getAnalogCalibrationState(DAQ::ChannelType::type_t type, + DAQ::index_t index) const final; + int setDigitalDirection(DAQ::index_t index, DAQ::direction_t direction) final; + + void read() final; + void write() final; + +private: + int fd; +}; + +class Driver : public DAQ::Driver +{ +public: + static DAQ::Driver* getInstance(); + void loadDevices() final; + void unloadDevices() final; + std::vector getDevices() final; + +private: + Driver(); + std::string version; + bool support_32_bit; + int total_board_count; + std::vector installed_boards; +}; + +Device::Device(const std::string& dev_name, + const std::vector& channels, + int device_file_descriptor) + : DAQ::Device(dev_name, channels) +{ + if(status < 0) { throw std::system_error("16AIO168 : could not open device"); } +} + +Device::~Device() +{ + aio168_close(this->fd); +} + +size_t Device::getChannelCount(DAQ::ChannelType::type_t type) const +{ + return physical_channels_registry.at(type).size(); +} + +bool Device::getChannelActive(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ + return physical_channels_registry.at(type).at(index).active; +} + +int Device::setChannelActive(DAQ::ChannelType::type_t type, + DAQ::index_t index, + bool state) +{ +} + +size_t Device::getAnalogRangeCount(DAQ::index_t /*index*/) const +{ +} + +size_t Device::getAnalogReferenceCount(DAQ::index_t /*index*/) const +{ +} + +size_t Device::getAnalogUnitsCount(DAQ::index_t /*index*/) const +{ +} + +size_t Device::getAnalogDownsample(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/) const +{ +} + +std::string Device::getAnalogRangeString(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t /*range*/) const +{ + +} + +std::string Device::getAnalogReferenceString(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t /*reference*/) const +{ +} + +std::string Device::getAnalogUnitsString(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t /*units*/) const +{ + +} + +double Device::getAnalogGain(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ +} + +double Device::getAnalogZeroOffset(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ +} + +DAQ::index_t Device::getAnalogRange(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ +} + +DAQ::index_t Device::getAnalogReference(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ +} + +DAQ::index_t Device::getAnalogUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ +} + +DAQ::index_t Device::getAnalogOffsetUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index) const +{ +} + +int Device::setAnalogGain(DAQ::ChannelType::type_t type, + DAQ::index_t index, + double gain) +{ +} + +int Device::setAnalogRange(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t range) +{ +} + +int Device::setAnalogZeroOffset(DAQ::ChannelType::type_t type, + DAQ::index_t index, + double offset) +{ +} + +int Device::setAnalogReference(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t reference) +{ +} + +int Device::setAnalogUnits(DAQ::ChannelType::type_t type, + DAQ::index_t index, + DAQ::index_t units) +{ + +} + +int Device::setAnalogOffsetUnits(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/, + DAQ::index_t /*units*/) +{ + return 0; +} + +int Device::setAnalogDownsample(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/, + size_t /*downsample*/) +{ + return 0; +} + +int Device::setAnalogCounter(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/) +{ + return 0; +} +int Device::setAnalogCalibrationValue(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/, + double /*value*/) +{ + return 0; +} +double Device::getAnalogCalibrationValue(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/) const +{ + return 0.0; +} +int Device::setAnalogCalibrationActive(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/, + bool /*state*/) +{ + return 0; +} +bool Device::getAnalogCalibrationActive(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/) const +{ + return false; +} +bool Device::getAnalogCalibrationState(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/) const +{ + return false; +} + +int Device::setDigitalDirection(DAQ::index_t /*index*/, + DAQ::direction_t /*direction*/) +{ + return 0; +} + +void Device::read() +{ + +} + +void Device::write() +{ + +} + +Driver::Driver() + : DAQ::Driver(std::string(DEFAULT_DRIVER_NAME)) +{ + int result = aio168_init(); + if(result < 0) { throw std::system_error(); } + this->loadDevices(); +} + +void Driver::loadDevices() +{ + constexpr std::string_view device_info_file = "/proc/16aio168"; + if(!std::filesystem::exists(device_info_file)){ + ERROR_MSG("DAQ::16aio168 : {} does not exist! Cannot discover available devices", device_info_file); + return; + } + std::ifstream file_stream(device_info_file); + std::string current_line; + std::vector tokens; + std::getline(file_stream, current_line); + std::vector parsed_line = split_string(current_line, ": "); + this->version = parsed_line[1]; + std::getline(file_stream, current_line); + parsed_line = split_string(current_line, ": "); + this->support_32_bit = parsed_line[1] == "yes"; + std::getline(file_stream, current_line); + parsed_line = split_string(current_line, ": "); + this->total_board_count = std::stoi(parsed_line[1]); + std::getline(file_stream, current_line); + parsed_line = split_string(current_line, ": "); + this->installed_boards = split_string(parsed_line, ","); + + // We query information from drivers and store into device during initialization + int result = 0; + int fd = 0; + int channel_count = 0; + std::vector channels; + for(int device_id = 0; device_id Driver::getDevices() +{ + std::ofstream file_stream("/proc/16aio168"); +} + +DAQ::Driver* Driver::getInstance() +{ + // if (instance == nullptr) { + // instance = new Driver(); + // } + static Driver instance; + return &instance; +} + +} // namespace + +extern "C" +{ +DAQ::Driver* getRTXIDAQDriver() +{ + return Driver::getInstance(); +} + +void deleteRTXIDAQDriver() {} +} From 16d77a89fa15a7b28978d7c34ed87c734e4bf533 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 26 Feb 2024 12:27:09 -0500 Subject: [PATCH 02/36] updated more gsc aio168 driver code --- src/gsc_aio168_driver.cpp | 330 ++++++++++++++++++++++++++++++++------ 1 file changed, 284 insertions(+), 46 deletions(-) diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp index 3dba6ff8b..fe4318a3a 100644 --- a/src/gsc_aio168_driver.cpp +++ b/src/gsc_aio168_driver.cpp @@ -1,4 +1,11 @@ +// General Standards Corporation does not define a standard location to install +// the library, so make sure the headers are saved in /usr/include/GSC and this +// should work +#include +#include +#include + #include #include @@ -37,6 +44,93 @@ inline std::vector split_string(const std::string& buffer, return split_tokens; } +inline void printError(int errcode) +{ + constexpr int ARRAY_SIZE = 1024; + std::array BUFFER {}; + strerror_r(errcode, BUFFER.data(), ARRAY_SIZE); + ERROR_MSG("16aio168 driver error with code {} : {}", errcode, BUFFER); +} + +// Define the struct that represents a physical channel, which is different than +// the block channel used by RTXI +struct physical_channel_t +{ + explicit physical_channel_t(std::string chan_name, + DAQ::ChannelType::type_t chan_type, + size_t chan_id) + : name(std::move(chan_name)) + , type(chan_type) + , id(chan_id) + { + } + std::string name; + DAQ::ChannelType::type_t type = DAQ::ChannelType::UNKNOWN; + size_t id; + DAQ::Reference::reference_t reference = DAQ::Reference::GROUND; + double offset = 0.0; + double gain = 1.0; + size_t range_index = 0; + size_t units_index = 0; + bool active = false; +}; + +inline int32_t index_to_reference(DAQ::index_t index) +{ + int32_t result = 0; + switch (static_cast(index)) { + case DAQ::Reference::GROUND: + case DAQ::Reference::COMMON: + result = AIO168_AI_MODE_SINGLE; + break; + case DAQ::Reference::DIFFERENTIAL: + result = AIO168_AI_MODE_DIFF; + break; + default: + result = AIO168_AI_MODE_SINGLE; + break; + } + return result; +} + +inline DAQ::Reference::reference_t reference_to_index(int32_t aio168_reference) +{ + DAQ::Reference::reference_t result = DAQ::Reference::UNKNOWN; + switch (aio168_reference) { + case AIO168_AI_MODE_SINGLE: + result = DAQ::Reference::GROUND; + break; + case AIO168_AI_MODE_DIFF: + result = DAQ::Reference::DIFFERENTIAL; + break; + default: + result = DAQ::Reference::OTHER; + break; + } + return result; +} + +inline DAQ::index_t range_to_index(int32_t aio168_range_id) +{ + DAQ::analog_range_t range; + const auto default_ranges = DAQ::get_default_ranges(); + switch (aio168_range_id) { + case AIO168_RANGE_2_5V: + range = DAQ::analog_range_t(-2.5, 2.5); + break; + case AIO168_RANGE_5V: + range = DAQ::analog_range_t(-5.0, 5.0); + break; + case AIO168_RANGE_10V: + default: + range = DAQ::analog_range_t(-10.0, 10.0); + break; + } + const auto* iter = + std::find(default_ranges.begin(), default_ranges.end(), range); + return iter == default_ranges.end() ? 0 : iter - default_ranges.begin(); +} + class Device final : public DAQ::Device { public: @@ -122,6 +216,20 @@ class Device final : public DAQ::Device private: int fd; + std::array, 4> physical_channels_registry; + // Used a tuple here because we want buffers to be in one place, and since not all + // IO is flaot, that meant we could not use a plain vector of vectors. Maybe we can + // just split them out to their own variables of same type for speed. + std::tuple, + std::vector, + std::vector, + std::vector> + buffer_arrays; + // Just trying to keep track of active channels for efficiency + std::array, DAQ::ChannelType::UNKNOWN> + active_channels; + + int CURRENT_SCAN_SIZE=1; }; class Driver : public DAQ::Driver @@ -136,21 +244,22 @@ class Driver : public DAQ::Driver Driver(); std::string version; bool support_32_bit; - int total_board_count; + size_t total_board_count; std::vector installed_boards; + std::vector m_devices; }; Device::Device(const std::string& dev_name, const std::vector& channels, int device_file_descriptor) : DAQ::Device(dev_name, channels) + , fd(device_file_descriptor) { - if(status < 0) { throw std::system_error("16AIO168 : could not open device"); } } Device::~Device() { - aio168_close(this->fd); + aio168_close(this->fd); } size_t Device::getChannelCount(DAQ::ChannelType::type_t type) const @@ -168,85 +277,206 @@ int Device::setChannelActive(DAQ::ChannelType::type_t type, DAQ::index_t index, bool state) { + physical_channels_registry.at(type).at(index).active = state; + active_channels.at(type).push_back(static_cast(index)); + if(type != DAQ::ChannelType::AI) { return 0; } + const int32_t max_input_port = *std::max(active_channels.at(type).begin(), + active_channels.at(type).end()); + int32_t scan_size = -1; + if(max_input_port <= 2){ + scan_size = AIO168_AI_SCAN_SIZE_0_1; + CURRENT_SCAN_SIZE = 2; + } else if(max_input_port <= 4) { + scan_size = AIO168_AI_SCAN_SIZE_0_3; + CURRENT_SCAN_SIZE = 4; + } else if(max_input_port <= 8) { + scan_size = AIO168_AI_SCAN_SIZE_0_7; + CURRENT_SCAN_SIZE = 8; + } else { + scan_size = AIO168_AI_SCAN_SIZE_0_15; + CURRENT_SCAN_SIZE = 16; + } + int result = aio168_ioctl(fd, AIO168_IOCTL_AI_SCAN_SIZE, &scan_size); + if(result < 0){ + printError(result); + } + return result; } -size_t Device::getAnalogRangeCount(DAQ::index_t /*index*/) const +size_t Device::getAnalogRangeCount(DAQ::index_t /*index*/) const { + // this device only supports 2.5, 5, and 10 ranges + return 3; } -size_t Device::getAnalogReferenceCount(DAQ::index_t /*index*/) const +size_t Device::getAnalogReferenceCount(DAQ::index_t /*index*/) const { + // this device only supports single ended and differential + return 2; } -size_t Device::getAnalogUnitsCount(DAQ::index_t /*index*/) const +size_t Device::getAnalogUnitsCount(DAQ::index_t /*index*/) const { + // this device only supports voltage + return 1; } size_t Device::getAnalogDownsample(DAQ::ChannelType::type_t /*type*/, DAQ::index_t /*index*/) const { + return 0; } std::string Device::getAnalogRangeString(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t /*range*/) const { - + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return ""; + } + const std::string formatting = "{:.1f}"; + auto [min, max] = DAQ::get_default_ranges().at( + physical_channels_registry.at(type).at(index).range_index); + return fmt::format(formatting, min) + std::string(" to ") + + fmt::format(formatting, max); } std::string Device::getAnalogReferenceString(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t /*reference*/) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return ""; + } + const int32_t ref = physical_channels_registry.at(type).at(index).reference; + std::string refstr; + switch (ref) { + case AIO168_AI_MODE_SINGLE: + refstr = "Ground"; + break; + case AIO168_AI_MODE_DIFF: + refstr = "Differential"; + break; + default: + refstr = "Other"; + break; + } + return refstr; + } std::string Device::getAnalogUnitsString(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t /*units*/) const { - + return "volts"; } double Device::getAnalogGain(DAQ::ChannelType::type_t type, DAQ::index_t index) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return 1.0; + } + return physical_channels_registry.at(type).at(index).gain; } double Device::getAnalogZeroOffset(DAQ::ChannelType::type_t type, DAQ::index_t index) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return 1.0; + } + return physical_channels_registry.at(type).at(index).offset; } DAQ::index_t Device::getAnalogRange(DAQ::ChannelType::type_t type, DAQ::index_t index) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return 0; + } + return physical_channels_registry.at(type).at(index).range_index; } DAQ::index_t Device::getAnalogReference(DAQ::ChannelType::type_t type, DAQ::index_t index) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return 0; + } + return reference_to_index( + physical_channels_registry.at(type).at(index).reference); } DAQ::index_t Device::getAnalogUnits(DAQ::ChannelType::type_t type, DAQ::index_t index) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return 0; + } + return physical_channels_registry.at(type).at(index).units_index; } DAQ::index_t Device::getAnalogOffsetUnits(DAQ::ChannelType::type_t type, DAQ::index_t index) const { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return 0; + } + return physical_channels_registry.at(type).at(index).units_index; } + + int Device::setAnalogGain(DAQ::ChannelType::type_t type, DAQ::index_t index, double gain) { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return -1; + } + // gain is handled by DAQ class and not nidaqmx + physical_channels_registry.at(type).at(index).gain = gain; + return 0; } int Device::setAnalogRange(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t range) { + if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { + return -1; + } + physical_channel_t& chan = physical_channels_registry.at(type).at(index); + if (!chan.active) { + chan.range_index = range; + return 0; + } + switch (range) { + case DAQ::ChannelType::AI: + set_analog_max = DAQmxSetAIMax; + set_analog_min = DAQmxSetAIMin; + break; + case DAQ::ChannelType::AO: + set_analog_max = DAQmxSetAOMax; + set_analog_min = DAQmxSetAOMin; + break; + default: + return -1; + } + // We attempt to change the range + printError(DAQmxStopTask(task)); + const int32_t max_result = set_analog_max(task, chan_name, max); + printError(max_result); + const int32_t min_result = set_analog_min(task, chan_name, min); + printError(min_result); + printError(DAQmxStartTask(task)); + if (max_result != 0 || min_result != 0) { + return -1; + } + chan.range_index = range; + return 0; } int Device::setAnalogZeroOffset(DAQ::ChannelType::type_t type, @@ -265,7 +495,6 @@ int Device::setAnalogUnits(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t units) { - } int Device::setAnalogOffsetUnits(DAQ::ChannelType::type_t /*type*/, @@ -321,31 +550,27 @@ int Device::setDigitalDirection(DAQ::index_t /*index*/, return 0; } -void Device::read() -{ - -} - -void Device::write() -{ +void Device::read() {} -} +void Device::write() {} Driver::Driver() : DAQ::Driver(std::string(DEFAULT_DRIVER_NAME)) { int result = aio168_init(); - if(result < 0) { throw std::system_error(); } - this->loadDevices(); -} - -void Driver::loadDevices() -{ - constexpr std::string_view device_info_file = "/proc/16aio168"; - if(!std::filesystem::exists(device_info_file)){ - ERROR_MSG("DAQ::16aio168 : {} does not exist! Cannot discover available devices", device_info_file); - return; + if (result < 0) { + printError(result); + throw std::runtime_error( + "16aio168 ERROR: Could not initialize 16aio168 drivers"); } + const std::string device_info_file = "/proc/16aio168"; + if (!std::filesystem::exists(device_info_file)) { + printError(result); + throw std::runtime_error(fmt::format( + "DAQ::16aio168 : {} does not exist! Cannot discover driver information", + device_info_file)); + } + // Parse Driver Information std::ifstream file_stream(device_info_file); std::string current_line; std::vector tokens; @@ -357,35 +582,46 @@ void Driver::loadDevices() this->support_32_bit = parsed_line[1] == "yes"; std::getline(file_stream, current_line); parsed_line = split_string(current_line, ": "); - this->total_board_count = std::stoi(parsed_line[1]); + this->total_board_count = static_cast(std::stoi(parsed_line[1])); std::getline(file_stream, current_line); parsed_line = split_string(current_line, ": "); - this->installed_boards = split_string(parsed_line, ","); + this->installed_boards = split_string(parsed_line[1], ","); + this->loadDevices(); +} - // We query information from drivers and store into device during initialization +void Driver::loadDevices() +{ + // We query information from drivers and store into device during + // initialization int result = 0; int fd = 0; int channel_count = 0; std::vector channels; - for(int device_id = 0; device_id(device_id), 0, &fd); + if (result < 0) { + printError(result); + ERROR_MSG("AIO168 DRIVER : Unable to open device {}. Skipping...", installed_boards[device_id]); continue; } result = aio168_ioctl(fd, AIO168_QUERY_CHAN_AI_MAX, &channel_count); - for(int channel_id = 0; channel_id < channel_count; channel_id++){ - channels.emplace_back({fmt::format("AI {}", channel_id), - fmt::format("Analog Input {}", channel_id), - IO::OUTPUT}); + for (int channel_id = 0; channel_id < channel_count; channel_id++) { + channels.emplace_back(fmt::format("AI {}", channel_id), + fmt::format("Analog Input {}", channel_id), + IO::OUTPUT); } result = aio168_ioctl(fd, AIO168_QUERY_CHAN_AO_MAX, &channel_count); - for(int channel_id = 0; channel_id < channel_count; channel_id++){ - channels.emplace_back({fmt::format("AO {}", channel_id), - fmt::format("Analog Output {}", channel_id), - IO::INPUT}); + for (int channel_id = 0; channel_id < channel_count; channel_id++) { + channels.emplace_back(fmt::format("AO {}", channel_id), + fmt::format("Analog Output {}", channel_id), + IO::INPUT); } + m_devices.emplace_back( + fmt::format("{}-{}", installed_boards[device_id], device_id), + channels, + fd); + channels.clear(); } } @@ -393,14 +629,16 @@ void Driver::unloadDevices() {} std::vector Driver::getDevices() { - std::ofstream file_stream("/proc/16aio168"); + std::vector devices; + devices.reserve(this->m_devices.size()); + for (auto& device : m_devices) { + devices.push_back(&device); + } + return devices; } DAQ::Driver* Driver::getInstance() { - // if (instance == nullptr) { - // instance = new Driver(); - // } static Driver instance; return &instance; } From ccf5ba52aac8e9a56c09c5e8fe43e7acf99a985c Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Tue, 27 Feb 2024 10:12:11 -0500 Subject: [PATCH 03/36] added relevant comments explaining nidaq driver logic --- src/nidaq_driver.cpp | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/src/nidaq_driver.cpp b/src/nidaq_driver.cpp index f939d577e..333d6ed6d 100644 --- a/src/nidaq_driver.cpp +++ b/src/nidaq_driver.cpp @@ -4,7 +4,6 @@ extern "C" #include } -#include #include #include @@ -321,13 +320,29 @@ class Device final : public DAQ::Device void write() final; private: + // RTXI uses 4 tasks, each with it's own different type: AI, AO, DI, DO. This is + // not our choice... it is required by NIDAQmx to get things going std::array task_list {}; + + // NIDAQmx channels are NOT the same as IO::Block channels used by RTXI. For example AI channels + // on NIDAQmx are physically entering the machine, but they are seen as output signals + // from the DAQ IO block in the read phase. std::array, DAQ::ChannelType::UNKNOWN> active_channels; + + // NIDAQmx will assign a unique name related to discovery order. Something like + // Dev1, Dev2, etc and two cards of the same type can be accessed with this. std::string internal_dev_name; + + // Some defaults that we don't bother providing flexibility for even though + // NIDAQmx can do that for us std::array, 4> physical_channels_registry; std::array default_ranges = DAQ::get_default_ranges(); std::array default_units = DAQ::get_default_units(); + + // Used a tuple here because we want buffers to be in one place, and since not all + // IO is flaot, that meant we could not use a plain vector of vectors. Maybe we can + // just split them out to their own variables of same type for speed. std::tuple, std::vector, std::vector, From 67fe190eba07c0c4e0c950aa7f3dea8d7419ba10 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Thu, 29 Feb 2024 13:41:53 -0500 Subject: [PATCH 04/36] Updated more driver logic. Changed rtxi search to include gsc driver. Updated installation rules to properly installed driver if device/library found --- CMakeLists.txt | 2 +- cmake/install-rules.cmake | 8 ++ src/CMakeLists.txt | 4 +- src/gsc_aio168_driver.cpp | 229 +++++++++++++++++++++++++++++--------- src/workspace.cpp | 5 + 5 files changed, 190 insertions(+), 58 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 159565669..8fe8d1c60 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,7 +70,7 @@ find_package(Threads REQUIRED) find_package(GSL REQUIRED) #Some libraries are harder to find as package, so this solves that find_library(nidaqmx NAMES libnidaqmx.so) -find_library(16aio168 NAMES lib16aio168_api.so) +find_library(16aio168_api NAMES lib16aio168_api.so) #Handle QT and boost libraries shenanigans set(CMAKE_AUTOMOC ON) diff --git a/cmake/install-rules.cmake b/cmake/install-rules.cmake index 7b8936ff6..d47bb3a78 100644 --- a/cmake/install-rules.cmake +++ b/cmake/install-rules.cmake @@ -23,6 +23,14 @@ install( ) endif() +if(16aio168_api) +install( + TARGETS rtxi_gsc16aio168_driver + DESTINATION ${CMAKE_INSTALL_BINDIR} + EXPORT rtxiLibraryTargets +) +endif() + install( FILES src/debug.hpp src/event.hpp src/io.hpp src/rt.hpp diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 4a9bb2a69..568f76d84 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -159,7 +159,7 @@ target_include_directories(rtxinidaqdriver target_link_libraries(rtxinidaqdriver PRIVATE nidaqmx rtxipal) endif() -if(16aio168) +if(16aio168_api) message("General Standards Corporation 16aio168 Driver API found") add_library(rtxi_gsc16aio168_driver MODULE gsc_aio168_driver.cpp @@ -171,7 +171,7 @@ target_include_directories(rtxi_gsc16aio168_driver "$" ) -target_link_libraries(rtxi_gsc16aio168_driver PRIVATE 16aio168 rtxipal) +target_link_libraries(rtxi_gsc16aio168_driver PRIVATE 16aio168_api rtxipal) endif() target_compile_features(rtxi PUBLIC cxx_std_17) diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp index fe4318a3a..86c448232 100644 --- a/src/gsc_aio168_driver.cpp +++ b/src/gsc_aio168_driver.cpp @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -16,6 +17,26 @@ constexpr std::string_view DEFAULT_DRIVER_NAME = "General Standards"; namespace { +constexpr int MAX_DIGITAL_LANES = + 4; // 16aio168 devices only have 4 digital lanes +constexpr int BYTE_RESOLUTION = 65536; // 2 ^ 16 bit symbols + +inline constexpr double binary_to_voltage(DAQ::analog_range_t volt_range, + int32_t value) +{ + const double width = (volt_range.second - volt_range.first) / BYTE_RESOLUTION; + const double offset = volt_range.first; + return (value & BYTE_RESOLUTION) * width - offset; +} + +inline constexpr int32_t voltage_to_binary(DAQ::analog_range_t volt_range, + double value) +{ + const double width = (volt_range.second - volt_range.first) / BYTE_RESOLUTION; + const double offset = volt_range.first; + return static_cast((value + offset) / width); +} + inline std::vector split_string(const std::string& buffer, const std::string& delim) { @@ -47,9 +68,9 @@ inline std::vector split_string(const std::string& buffer, inline void printError(int errcode) { constexpr int ARRAY_SIZE = 1024; - std::array BUFFER {}; + std::string BUFFER(ARRAY_SIZE, '\0'); strerror_r(errcode, BUFFER.data(), ARRAY_SIZE); - ERROR_MSG("16aio168 driver error with code {} : {}", errcode, BUFFER); + ERROR_MSG("AIO168 driver error with code {} : {}", errcode, BUFFER); } // Define the struct that represents a physical channel, which is different than @@ -131,6 +152,24 @@ inline DAQ::index_t range_to_index(int32_t aio168_range_id) return iter == default_ranges.end() ? 0 : iter - default_ranges.begin(); } +inline int32_t index_to_range(DAQ::index_t index) +{ + int32_t range; + switch (index) { + case 2: + range = AIO168_RANGE_2_5V; + break; + case 1: + range = AIO168_RANGE_5V; + break; + case 0: + default: + range = AIO168_RANGE_10V; + break; + } + return range; +} + class Device final : public DAQ::Device { public: @@ -217,19 +256,16 @@ class Device final : public DAQ::Device private: int fd; std::array, 4> physical_channels_registry; - // Used a tuple here because we want buffers to be in one place, and since not all - // IO is flaot, that meant we could not use a plain vector of vectors. Maybe we can - // just split them out to their own variables of same type for speed. - std::tuple, - std::vector, - std::vector, - std::vector> - buffer_arrays; + std::vector ai_channels_buffer; + std::vector ao_channels_buffer; + std::vector di_channels_buffer; + std::vector do_channels_buffer; + std::array default_ranges; + // Just trying to keep track of active channels for efficiency - std::array, DAQ::ChannelType::UNKNOWN> - active_channels; + std::array, DAQ::ChannelType::UNKNOWN> active_channels; - int CURRENT_SCAN_SIZE=1; + size_t CURRENT_SCAN_SIZE = 16; }; class Driver : public DAQ::Driver @@ -255,6 +291,57 @@ Device::Device(const std::string& dev_name, : DAQ::Device(dev_name, channels) , fd(device_file_descriptor) { + int32_t max_ai_count = AIO168_QUERY_CHAN_AI_MAX; + int32_t max_ao_count = AIO168_QUERY_CHAN_AO_MAX; + int result = aio168_ioctl(fd, AIO168_IOCTL_QUERY, &max_ai_count); + if (result < 0) { + printError(result); + throw std::runtime_error( + "AIO168 DRIVER : Unable to obtain max AI channel count"); + } + result = aio168_ioctl(fd, AIO168_IOCTL_QUERY, &max_ao_count); + if (result < 0) { + printError(result); + throw std::runtime_error( + "AIO168 DRIVER : Unable to obtain max AO channel count"); + } + std::string chan_name; + for (int ai_count = 0; ai_count < max_ai_count; ai_count++) { + physical_channels_registry.at(DAQ::ChannelType::AI) + .emplace_back( + fmt::format("AI{}", ai_count), DAQ::ChannelType::AI, ai_count); + } + for (int ao_count = 0; ao_count < max_ao_count; ao_count++) { + physical_channels_registry.at(DAQ::ChannelType::AO) + .emplace_back( + fmt::format("AO{}", ao_count), DAQ::ChannelType::AO, ao_count); + } + for (int digital_lane = 0; digital_lane < MAX_DIGITAL_LANES; digital_lane++) { + physical_channels_registry.at(DAQ::ChannelType::DI) + .emplace_back(fmt::format("DI{}", digital_lane), + DAQ::ChannelType::DI, + digital_lane); + physical_channels_registry.at(DAQ::ChannelType::DO) + .emplace_back(fmt::format("DO{}", digital_lane), + DAQ::ChannelType::DO, + digital_lane); + } + + // We need to tell the board that channel scanning is software timed. + // Check 16aio168 manual for explenation of this setting + int32_t scan_setting = AIO168_AI_SCAN_CLK_SRC_BCR; + result = aio168_ioctl(fd, AIO168_IOCTL_AI_SCAN_CLK_SRC, &scan_setting); + if(result < 0){ + ERROR_MSG("16QIO168 DRIVER : Unable to set the channel scan to software trigger for device"); + printError(result); + } + + ai_channels_buffer.assign(getChannelCount(DAQ::ChannelType::AI), 0); + ao_channels_buffer.assign(getChannelCount(DAQ::ChannelType::AO), 0); + di_channels_buffer.assign(getChannelCount(DAQ::ChannelType::DI), 0); + do_channels_buffer.assign(getChannelCount(DAQ::ChannelType::DO), 0); + default_ranges = DAQ::get_default_ranges(); + this->setActive(/*act=*/true); } Device::~Device() @@ -279,17 +366,19 @@ int Device::setChannelActive(DAQ::ChannelType::type_t type, { physical_channels_registry.at(type).at(index).active = state; active_channels.at(type).push_back(static_cast(index)); - if(type != DAQ::ChannelType::AI) { return 0; } + if (type != DAQ::ChannelType::AI) { + return 0; + } const int32_t max_input_port = *std::max(active_channels.at(type).begin(), active_channels.at(type).end()); int32_t scan_size = -1; - if(max_input_port <= 2){ + if (max_input_port <= 2) { scan_size = AIO168_AI_SCAN_SIZE_0_1; CURRENT_SCAN_SIZE = 2; - } else if(max_input_port <= 4) { + } else if (max_input_port <= 4) { scan_size = AIO168_AI_SCAN_SIZE_0_3; CURRENT_SCAN_SIZE = 4; - } else if(max_input_port <= 8) { + } else if (max_input_port <= 8) { scan_size = AIO168_AI_SCAN_SIZE_0_7; CURRENT_SCAN_SIZE = 8; } else { @@ -297,25 +386,25 @@ int Device::setChannelActive(DAQ::ChannelType::type_t type, CURRENT_SCAN_SIZE = 16; } int result = aio168_ioctl(fd, AIO168_IOCTL_AI_SCAN_SIZE, &scan_size); - if(result < 0){ + if (result < 0) { printError(result); } return result; } -size_t Device::getAnalogRangeCount(DAQ::index_t /*index*/) const +size_t Device::getAnalogRangeCount(DAQ::index_t /*index*/) const { // this device only supports 2.5, 5, and 10 ranges return 3; } -size_t Device::getAnalogReferenceCount(DAQ::index_t /*index*/) const +size_t Device::getAnalogReferenceCount(DAQ::index_t /*index*/) const { // this device only supports single ended and differential return 2; } -size_t Device::getAnalogUnitsCount(DAQ::index_t /*index*/) const +size_t Device::getAnalogUnitsCount(DAQ::index_t /*index*/) const { // this device only supports voltage return 1; @@ -362,7 +451,6 @@ std::string Device::getAnalogReferenceString(DAQ::ChannelType::type_t type, break; } return refstr; - } std::string Device::getAnalogUnitsString(DAQ::ChannelType::type_t type, @@ -427,8 +515,6 @@ DAQ::index_t Device::getAnalogOffsetUnits(DAQ::ChannelType::type_t type, return physical_channels_registry.at(type).at(index).units_index; } - - int Device::setAnalogGain(DAQ::ChannelType::type_t type, DAQ::index_t index, double gain) @@ -453,27 +539,14 @@ int Device::setAnalogRange(DAQ::ChannelType::type_t type, chan.range_index = range; return 0; } - switch (range) { - case DAQ::ChannelType::AI: - set_analog_max = DAQmxSetAIMax; - set_analog_min = DAQmxSetAIMin; - break; - case DAQ::ChannelType::AO: - set_analog_max = DAQmxSetAOMax; - set_analog_min = DAQmxSetAOMin; - break; - default: - return -1; - } - // We attempt to change the range - printError(DAQmxStopTask(task)); - const int32_t max_result = set_analog_max(task, chan_name, max); - printError(max_result); - const int32_t min_result = set_analog_min(task, chan_name, min); - printError(min_result); - printError(DAQmxStartTask(task)); - if (max_result != 0 || min_result != 0) { - return -1; + int gsc_range_value = index_to_range(range); + int result = aio168_ioctl(fd, AIO168_IOCTL_RANGE, &gsc_range_value); + if (result < 0) { + ERROR_MSG("AIO168 ERROR : Unable to set range for device {}", getName()); + printError(result); + int32_t retrieve = -1; + result = aio168_ioctl(fd, AIO168_IOCTL_RANGE, &retrieve); + chan.range_index = range_to_index(retrieve); } chan.range_index = range; return 0; @@ -483,18 +556,22 @@ int Device::setAnalogZeroOffset(DAQ::ChannelType::type_t type, DAQ::index_t index, double offset) { + physical_channel_t& chan = physical_channels_registry.at(type).at(index); + chan.offset = offset; } int Device::setAnalogReference(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t reference) { + return 0; } int Device::setAnalogUnits(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t units) { + return 0; } int Device::setAnalogOffsetUnits(DAQ::ChannelType::type_t /*type*/, @@ -516,6 +593,7 @@ int Device::setAnalogCounter(DAQ::ChannelType::type_t /*type*/, { return 0; } + int Device::setAnalogCalibrationValue(DAQ::ChannelType::type_t /*type*/, DAQ::index_t /*index*/, double /*value*/) @@ -550,9 +628,48 @@ int Device::setDigitalDirection(DAQ::index_t /*index*/, return 0; } -void Device::read() {} +void Device::read() +{ + // initiate scan + aio168_ioctl(fd, AIO168_IOCTL_AI_SYNC, nullptr); + DAQ::analog_range_t range {}; + int samples_read = 0; + double gain = 1.0; + double offset = 0.0; + samples_read = aio168_read( + fd, ai_channels_buffer.data(), CURRENT_SCAN_SIZE * sizeof(int32_t)); + // we have to convert some stuff to float first before we continue + for (size_t chan_id = 0; chan_id < CURRENT_SCAN_SIZE; chan_id++) { + auto& chan_info = physical_channels_registry[DAQ::ChannelType::AI][chan_id]; + range = default_ranges[chan_info.range_index]; + gain = chan_info.gain; + offset = chan_info.offset; + writeoutput( + chan_id, + binary_to_voltage(range, ai_channels_buffer[chan_id]) * gain + offset); + } +} -void Device::write() {} +void Device::write() +{ + DAQ::analog_range_t range {}; + int samples_written = 0; + double gain = 1.0; + double offset = 0.0; + double value = 0.0; + for (size_t chan_id = 0; chan_id < ao_channels_buffer.size(); chan_id++) { + // we have to saturate value before pushing to output + value = std::min(std::max(readinput(chan_id), range.first), range.second); + + } + int samples_written = 0; + samples_written = aio168_write( + fd, ai_channels_buffer.data(), CURRENT_SCAN_SIZE * sizeof(int32_t), ); + for (int chan_id = 0; chan_id < ai_channels_buffer.size(); chan_id++) { + writeoutput(chan_id, + ai_channels_buffer[chan_id] * chan->gain + chan->offset); + } +} Driver::Driver() : DAQ::Driver(std::string(DEFAULT_DRIVER_NAME)) @@ -605,17 +722,19 @@ void Driver::loadDevices() installed_boards[device_id]); continue; } - result = aio168_ioctl(fd, AIO168_QUERY_CHAN_AI_MAX, &channel_count); + channel_count = AIO168_QUERY_CHAN_AI_MAX; + result = aio168_ioctl(fd, AIO168_IOCTL_QUERY, &channel_count); for (int channel_id = 0; channel_id < channel_count; channel_id++) { - channels.emplace_back(fmt::format("AI {}", channel_id), - fmt::format("Analog Input {}", channel_id), - IO::OUTPUT); + channels.push_back({fmt::format("AI {}", channel_id), + fmt::format("Analog Input {}", channel_id), + IO::OUTPUT}); } - result = aio168_ioctl(fd, AIO168_QUERY_CHAN_AO_MAX, &channel_count); + channel_count = AIO168_QUERY_CHAN_AO_MAX; + result = aio168_ioctl(fd, AIO168_IOCTL_QUERY, &channel_count); for (int channel_id = 0; channel_id < channel_count; channel_id++) { - channels.emplace_back(fmt::format("AO {}", channel_id), - fmt::format("Analog Output {}", channel_id), - IO::INPUT); + channels.push_back({fmt::format("AO {}", channel_id), + fmt::format("Analog Output {}", channel_id), + IO::INPUT}); } m_devices.emplace_back( fmt::format("{}-{}", installed_boards[device_id], device_id), diff --git a/src/workspace.cpp b/src/workspace.cpp index 3c935ea1d..c0410e799 100644 --- a/src/workspace.cpp +++ b/src/workspace.cpp @@ -61,6 +61,11 @@ Workspace::Manager::Manager(Event::Manager* ev_manager) this->registerDriver(bin_dir.path().toStdString() + std::string("/") + nidaq_driver_name); } + const std::string gsc_driver_name = "librtxi_gsc16aio168_driver.so"; + if (bin_dir.exists(QString::fromStdString(gsc_driver_name))) { + this->registerDriver(bin_dir.path().toStdString() + std::string("/") + + gsc_driver_name); + } } Workspace::Manager::~Manager() From 3b3033adc4ed24b39a86bf01da672f767c8fa764 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Thu, 14 Mar 2024 14:30:56 -0400 Subject: [PATCH 05/36] fixed bug in read/write stage of the driver --- src/gsc_aio168_driver.cpp | 45 +++++++++++++++++++++------------------ 1 file changed, 24 insertions(+), 21 deletions(-) diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp index 86c448232..37ef5ef7d 100644 --- a/src/gsc_aio168_driver.cpp +++ b/src/gsc_aio168_driver.cpp @@ -96,10 +96,10 @@ struct physical_channel_t bool active = false; }; -inline int32_t index_to_reference(DAQ::index_t index) +inline int32_t daqref_to_gslref(DAQ::Reference::reference_t index) { int32_t result = 0; - switch (static_cast(index)) { + switch (index) { case DAQ::Reference::GROUND: case DAQ::Reference::COMMON: result = AIO168_AI_MODE_SINGLE; @@ -114,7 +114,7 @@ inline int32_t index_to_reference(DAQ::index_t index) return result; } -inline DAQ::Reference::reference_t reference_to_index(int32_t aio168_reference) +inline DAQ::Reference::reference_t gslref_to_daqref(int32_t aio168_reference) { DAQ::Reference::reference_t result = DAQ::Reference::UNKNOWN; switch (aio168_reference) { @@ -154,7 +154,7 @@ inline DAQ::index_t range_to_index(int32_t aio168_range_id) inline int32_t index_to_range(DAQ::index_t index) { - int32_t range; + int32_t range = 0; switch (index) { case 2: range = AIO168_RANGE_2_5V; @@ -331,8 +331,10 @@ Device::Device(const std::string& dev_name, // Check 16aio168 manual for explenation of this setting int32_t scan_setting = AIO168_AI_SCAN_CLK_SRC_BCR; result = aio168_ioctl(fd, AIO168_IOCTL_AI_SCAN_CLK_SRC, &scan_setting); - if(result < 0){ - ERROR_MSG("16QIO168 DRIVER : Unable to set the channel scan to software trigger for device"); + if (result < 0) { + ERROR_MSG( + "16QIO168 DRIVER : Unable to set the channel scan to software trigger " + "for device"); printError(result); } @@ -493,7 +495,7 @@ DAQ::index_t Device::getAnalogReference(DAQ::ChannelType::type_t type, if (type == DAQ::ChannelType::DI || type == DAQ::ChannelType::DO) { return 0; } - return reference_to_index( + return gslref_to_daqref( physical_channels_registry.at(type).at(index).reference); } @@ -558,18 +560,21 @@ int Device::setAnalogZeroOffset(DAQ::ChannelType::type_t type, { physical_channel_t& chan = physical_channels_registry.at(type).at(index); chan.offset = offset; + return 0; } int Device::setAnalogReference(DAQ::ChannelType::type_t type, DAQ::index_t index, DAQ::index_t reference) { + physical_channel_t& chan = physical_channels_registry.at(type).at(index); + chan.reference = static_cast(reference); return 0; } -int Device::setAnalogUnits(DAQ::ChannelType::type_t type, - DAQ::index_t index, - DAQ::index_t units) +int Device::setAnalogUnits(DAQ::ChannelType::type_t /*type*/, + DAQ::index_t /*index*/, + DAQ::index_t /*units*/) { return 0; } @@ -633,10 +638,9 @@ void Device::read() // initiate scan aio168_ioctl(fd, AIO168_IOCTL_AI_SYNC, nullptr); DAQ::analog_range_t range {}; - int samples_read = 0; double gain = 1.0; double offset = 0.0; - samples_read = aio168_read( + aio168_read( fd, ai_channels_buffer.data(), CURRENT_SCAN_SIZE * sizeof(int32_t)); // we have to convert some stuff to float first before we continue for (size_t chan_id = 0; chan_id < CURRENT_SCAN_SIZE; chan_id++) { @@ -653,22 +657,21 @@ void Device::read() void Device::write() { DAQ::analog_range_t range {}; - int samples_written = 0; double gain = 1.0; double offset = 0.0; double value = 0.0; for (size_t chan_id = 0; chan_id < ao_channels_buffer.size(); chan_id++) { // we have to saturate value before pushing to output + auto& chan_info = physical_channels_registry[DAQ::ChannelType::AO][chan_id]; + range = default_ranges[chan_info.range_index]; + gain = chan_info.gain; + offset = chan_info.offset; value = std::min(std::max(readinput(chan_id), range.first), range.second); - - } - int samples_written = 0; - samples_written = aio168_write( - fd, ai_channels_buffer.data(), CURRENT_SCAN_SIZE * sizeof(int32_t), ); - for (int chan_id = 0; chan_id < ai_channels_buffer.size(); chan_id++) { - writeoutput(chan_id, - ai_channels_buffer[chan_id] * chan->gain + chan->offset); + ao_channels_buffer[chan_id] = + voltage_to_binary(range, value * gain + offset); } + aio168_write( + fd, ai_channels_buffer.data(), CURRENT_SCAN_SIZE * sizeof(int32_t)); } Driver::Driver() From 888d5339b3f34947a892dc04d19fcec52c2bf5a1 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Wed, 20 Mar 2024 11:41:31 -0400 Subject: [PATCH 06/36] Further updates to 16aio168 driver. Now supports analog input/output --- src/gsc_aio168_driver.cpp | 66 ++++++++++++++++++++++++++++++++------- 1 file changed, 54 insertions(+), 12 deletions(-) diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp index 37ef5ef7d..b434c73e5 100644 --- a/src/gsc_aio168_driver.cpp +++ b/src/gsc_aio168_driver.cpp @@ -19,21 +19,21 @@ namespace constexpr int MAX_DIGITAL_LANES = 4; // 16aio168 devices only have 4 digital lanes -constexpr int BYTE_RESOLUTION = 65536; // 2 ^ 16 bit symbols +constexpr int BYTE_RESOLUTION = 65535; // 2 ^ 16 bit symbols inline constexpr double binary_to_voltage(DAQ::analog_range_t volt_range, int32_t value) { const double width = (volt_range.second - volt_range.first) / BYTE_RESOLUTION; - const double offset = volt_range.first; - return (value & BYTE_RESOLUTION) * width - offset; + const double offset = (volt_range.second - volt_range.first) / 2.0; + return static_cast(value & BYTE_RESOLUTION) * width - offset; } inline constexpr int32_t voltage_to_binary(DAQ::analog_range_t volt_range, double value) { const double width = (volt_range.second - volt_range.first) / BYTE_RESOLUTION; - const double offset = volt_range.first; + const double offset = (volt_range.second - volt_range.first) / 2.0; return static_cast((value + offset) / width); } @@ -265,7 +265,7 @@ class Device final : public DAQ::Device // Just trying to keep track of active channels for efficiency std::array, DAQ::ChannelType::UNKNOWN> active_channels; - size_t CURRENT_SCAN_SIZE = 16; + size_t CURRENT_SCAN_SIZE = 0; }; class Driver : public DAQ::Driver @@ -338,11 +338,37 @@ Device::Device(const std::string& dev_name, printError(result); } + //int32_t sync_setting = AIO168_AO_BURST_CLK_SRC_BCR; + //result = aio168_ioctl(fd, AIO168_IOCTL_AO_BURST_CLK_SRC, &sync_setting); + //if (result < 0) { + // ERROR_MSG( + // "16QIO168 DRIVER : Unable to set the channel sync to software trigger " + // "for device"); + // printError(result); + //} + //int32_t timing = AIO168_AO_TIMING_SIMUL; + //result = aio168_ioctl(fd, AIO168_IOCTL_AO_TIMING, &timing); + //if (result < 0) { + // ERROR_MSG( + // "16QIO168 DRIVER : Unable to set the channel sync to simultanous output " + // "for device"); + // printError(result); + //} + ai_channels_buffer.assign(getChannelCount(DAQ::ChannelType::AI), 0); ao_channels_buffer.assign(getChannelCount(DAQ::ChannelType::AO), 0); di_channels_buffer.assign(getChannelCount(DAQ::ChannelType::DI), 0); do_channels_buffer.assign(getChannelCount(DAQ::ChannelType::DO), 0); default_ranges = DAQ::get_default_ranges(); + + // Calibrate the device + // result = aio168_ioctl(fd, AIO168_IOCTL_AUTOCAL, nullptr); + + // Don't let the device sleep when reading and just return immediately + int32_t timeout = 0; + result = aio168_ioctl(fd, AIO168_IOCTL_RX_IO_TIMEOUT, &timeout); + //timeout = 0; + //result = aio168_ioctl(fd, AIO168_IOCTL_TX_IO_TIMEOUT, &timeout); this->setActive(/*act=*/true); } @@ -366,11 +392,23 @@ int Device::setChannelActive(DAQ::ChannelType::type_t type, DAQ::index_t index, bool state) { + auto iter = std::find(active_channels.at(type).begin(), + active_channels.at(type).end(), + static_cast(index)); physical_channels_registry.at(type).at(index).active = state; - active_channels.at(type).push_back(static_cast(index)); + if(state){ + if(iter == active_channels.at(type).end()) { active_channels.at(type).push_back(static_cast(index)); } + } else { + if(iter != active_channels.at(type).end()) { active_channels.at(type).erase(iter); } + } + if (type != DAQ::ChannelType::AI) { return 0; } + if(active_channels.at(type).empty()) { + CURRENT_SCAN_SIZE = 0; + return 0; + } const int32_t max_input_port = *std::max(active_channels.at(type).begin(), active_channels.at(type).end()); int32_t scan_size = -1; @@ -645,6 +683,7 @@ void Device::read() // we have to convert some stuff to float first before we continue for (size_t chan_id = 0; chan_id < CURRENT_SCAN_SIZE; chan_id++) { auto& chan_info = physical_channels_registry[DAQ::ChannelType::AI][chan_id]; + if(!chan_info.active) { continue; } range = default_ranges[chan_info.range_index]; gain = chan_info.gain; offset = chan_info.offset; @@ -666,12 +705,14 @@ void Device::write() range = default_ranges[chan_info.range_index]; gain = chan_info.gain; offset = chan_info.offset; - value = std::min(std::max(readinput(chan_id), range.first), range.second); - ao_channels_buffer[chan_id] = - voltage_to_binary(range, value * gain + offset); + value = std::min(std::max(readinput(chan_id) * gain + offset, range.first), range.second); + ao_channels_buffer[chan_id] = voltage_to_binary(range, value) | chan_id << 16; } + ao_channels_buffer.back() |= 1 << 19; aio168_write( - fd, ai_channels_buffer.data(), CURRENT_SCAN_SIZE * sizeof(int32_t)); + fd, ao_channels_buffer.data(), ao_channels_buffer.size() * sizeof(int32_t)); + // initate output sync + // aio168_ioctl(fd, AIO168_IOCTL_AO_SYNC, nullptr); } Driver::Driver() @@ -687,8 +728,9 @@ Driver::Driver() if (!std::filesystem::exists(device_info_file)) { printError(result); throw std::runtime_error(fmt::format( - "DAQ::16aio168 : {} does not exist! Cannot discover driver information", - device_info_file)); + "DAQ::16aio168 : {} does not exist! Cannot discover driver information \n{}", + device_info_file, + "Make sure that the 16aio168 module is loaded before continuing. You can do this by runnign ./script in the driver directory.")); } // Parse Driver Information std::ifstream file_stream(device_info_file); From 9c4459c28ec006e2dd65e9b35c33b09a7c755965 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Thu, 21 Mar 2024 17:29:57 -0400 Subject: [PATCH 07/36] changing api to handle loading multiple plugins in settings logic --- src/event.cpp | 9 +++---- src/event.hpp | 3 +-- src/main_window.cpp | 66 +++++++++++++++++++++++++++++++++++++++++++-- src/workspace.cpp | 54 +++++++------------------------------ src/workspace.hpp | 13 +++------ 5 files changed, 81 insertions(+), 64 deletions(-) diff --git a/src/event.cpp b/src/event.cpp index fdb0be301..776913388 100644 --- a/src/event.cpp +++ b/src/event.cpp @@ -99,13 +99,10 @@ std::string Event::type_to_string(Event::Type event_type) return_string = "WIDGET : plugin remove"; break; case Event::Type::DAQ_DEVICE_QUERY_EVENT: - return_string = "MANAGER : daq query event"; + return_string = "WORKSPACE : daq query event"; break; - case Event::Type::SETTINGS_OBJECT_INSERT_EVENT: - return_string = "SYSTEM : settings object insert"; - break; - case Event::Type::SETTINGS_OBJECT_REMOVE_EVENT: - return_string = "SYSTEM : settings object remove"; + case Event::Type::PLUGIN_LIST_QUERY_EVENT: + return_string = "WORKSPACE : plugin list request event"; break; case Event::Type::OPEN_FILE_EVENT: return_string = "SYSTEM : open file"; diff --git a/src/event.hpp b/src/event.hpp index f6f052288..fb6d18188 100644 --- a/src/event.hpp +++ b/src/event.hpp @@ -77,8 +77,7 @@ enum Type PLUGIN_INSERT_EVENT, PLUGIN_REMOVE_EVENT, DAQ_DEVICE_QUERY_EVENT, - SETTINGS_OBJECT_INSERT_EVENT, - SETTINGS_OBJECT_REMOVE_EVENT, + PLUGIN_LIST_QUERY_EVENT, OPEN_FILE_EVENT, START_RECORDING_EVENT, STOP_RECORDING_EVENT, diff --git a/src/main_window.cpp b/src/main_window.cpp index ad2deff79..716bcbe60 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -361,7 +361,7 @@ void MainWindow::loadSettings() this, tr("Load saved workspace"), userprefs.value("/dirs/setfiles", env_var).toString(), - tr("Settings (*.set)")); + tr("Settings (*.ini)")); if (QFile(filename).exists()) { systemMenu->clear(); @@ -369,6 +369,13 @@ void MainWindow::loadSettings() } } +template +struct overload : Ts... +{ + using Ts::operator()...; +}; +template +overload(Ts...) -> overload; void MainWindow::saveSettings() { QSettings userprefs; @@ -379,8 +386,63 @@ void MainWindow::saveSettings() save_settings_dialog->setComboBoxItems(userprefs.childGroups()); save_settings_dialog->setLabelText("Profile"); save_settings_dialog->setOkButtonText("Save"); - userprefs.endGroup(); save_settings_dialog->exec(); + + const QString profile_name = save_settings_dialog->textValue(); + if(userprefs.childGroups().contains(profile_name)) { userprefs.remove(profile_name); } + userprefs.beginGroup(profile_name); + + // get period and save + Event::Object get_period_event(Event::Type::RT_GET_PERIOD_EVENT); + event_manager->postEvent(&get_period_event); + const auto period = std::any_cast(get_period_event.getParam("period")); + userprefs.setValue("period", QString::number(period)); + + // Safe DAQ userprefs + userprefs.beginGroup("DAQs"); + userprefs.endGroup(); + + // Safe Widget userprefs + userprefs.beginGroup("Widgets"); + QString widget_name; + int widget_count = 0; + Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); + this->event_manager->postEvent(&loaded_plugins_query); + const auto plugin_list = std::any_cast>(loaded_plugins_query.getParam("plugins")); + for (const auto& entry : plugin_list) { + widget_name = QString::fromStdString(entry->getName()); + userprefs.beginGroup(widget_name); + for (const auto& plugin : entry.second) { + userprefs.setValue("library", QString::fromStdString(plugin->getLibrary())); + userprefs.beginGroup(QString::number(widget_count)); + for (const auto& param_info : plugin->getComponentParametersInfo()) { + userprefs.setValue( + QString::fromStdString(param_info.name), + std::visit(overload {[](const int64_t& val) -> QString + { return QString::number(val); }, + [](const double& val) -> QString + { return QString::number(val); }, + [](const uint64_t& val) -> QString + { return QString::number(val); }, + [](const std::string& val) -> QString + { return QString::fromStdString(val); }, + [](const RT::State::state_t& val) -> QString { + return QString::number( + static_cast(val)); + }}, + param_info.value)); + } + userprefs.endGroup(); + widget_count++; + } + userprefs.endGroup(); + } + userprefs.endGroup(); // Widgets + + userprefs.beginGroup("Connections"); + userprefs.endGroup(); // Connections + userprefs.endGroup(); // profile + userprefs.endGroup(); // Workspaces } void MainWindow::resetSettings() diff --git a/src/workspace.cpp b/src/workspace.cpp index 3c935ea1d..e3f4abbb5 100644 --- a/src/workspace.cpp +++ b/src/workspace.cpp @@ -13,7 +13,6 @@ */ #include -#include #include "workspace.hpp" @@ -133,52 +132,16 @@ std::vector Workspace::Manager::getAllDevices() return devices; } -template -struct overload : Ts... -{ - using Ts::operator()...; -}; -template -overload(Ts...) -> overload; -void Workspace::Manager::saveSettings(const QString& profile_name) + +std::vector Workspace::Manager::getLoadedPlugins() { - QSettings settings(settings_prefix + profile_name, QSettings::IniFormat); - settings.beginGroup("widgets"); - QString widget_name; - int widget_count = 0; - for (const auto& entry : this->rtxi_widgets_registry) { - widget_name = QString::fromStdString(entry.first); - settings.beginGroup(widget_name); - for (const auto& plugin : entry.second) { - settings.beginGroup(QString::number(widget_count)); - for (const auto& param_info : plugin->getComponentParametersInfo()) { - settings.setValue( - QString::fromStdString(param_info.name), - std::visit(overload {[](const int64_t& val) -> QString - { return QString::number(val); }, - [](const double& val) -> QString - { return QString::number(val); }, - [](const uint64_t& val) -> QString - { return QString::number(val); }, - [](const std::string& val) -> QString - { return QString::fromStdString(val); }, - [](const RT::State::state_t& val) -> QString { - return QString::number( - static_cast(val)); - }}, - param_info.value)); - } - settings.endGroup(); - widget_count++; + std::vector result; + for(const auto& entry : this->rtxi_widgets_registry){ + for(const auto& plugin : entry.second){ + result.push_back(plugin.get()); } - settings.endGroup(); } - settings.endGroup(); -} - -void Workspace::Manager::loadSettings(const QString& profile_name) -{ - QSettings settings(profile_name, QSettings::IniFormat); + return result; } Widgets::Plugin* Workspace::Manager::loadCorePlugin(const std::string& library) @@ -410,6 +373,9 @@ void Workspace::Manager::receiveEvent(Event::Object* event) case Event::Type::DAQ_DEVICE_QUERY_EVENT: event->setParam("devices", std::any(this->getAllDevices())); break; + case Event::Type::PLUGIN_LIST_QUERY_EVENT: + event->setParam("plugins", std::any(this->getLoadedPlugins())); + break; default: return; } diff --git a/src/workspace.hpp b/src/workspace.hpp index ee4fb0bb2..145b3ede2 100644 --- a/src/workspace.hpp +++ b/src/workspace.hpp @@ -111,18 +111,11 @@ class Manager : public Event::Handler std::vector getAllDevices(); /*! - * Save current workspace values and state settings + * Get list of loaded plugins * - * \param profile_name The name to save the settings + * \return A vector of pointers to constant Widget::Plugin objects */ - void saveSettings(const QString& profile_name); - - /*! - * Restore workspace values and state settings - * - * \param profile_name The name of the stored settings - */ - void loadSettings(const QString& profile_name); + std::vector getLoadedPlugins(); private: using driver_registry_entry = std::pair; From a7a32e4bb224f09caa59bf13b1fbc8ff5ed8dcaf Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 29 Mar 2024 14:40:41 -0400 Subject: [PATCH 08/36] more improvements to settings save and load logic --- src/main_window.cpp | 72 +++++++++++++++++++++------------------------ src/widgets.cpp | 2 +- src/widgets.hpp | 2 +- 3 files changed, 35 insertions(+), 41 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index 716bcbe60..5d347480f 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -354,19 +354,20 @@ void MainWindow::loadWindow() void MainWindow::loadSettings() { - const QSettings userprefs; - const QString env_var = QString::fromLocal8Bit(qgetenv("HOME")); - - const QString filename = QFileDialog::getOpenFileName( - this, - tr("Load saved workspace"), - userprefs.value("/dirs/setfiles", env_var).toString(), - tr("Settings (*.ini)")); - - if (QFile(filename).exists()) { - systemMenu->clear(); - mdiArea->closeAllSubWindows(); + QSettings userprefs; + userprefs.beginGroup("Workspaces"); + auto* load_settings_dialog = new QInputDialog(this); + load_settings_dialog->setInputMode(QInputDialog::TextInput); + load_settings_dialog->setComboBoxEditable(false); + load_settings_dialog->setComboBoxItems(userprefs.childGroups()); + load_settings_dialog->setLabelText("Profile"); + load_settings_dialog->setOkButtonText("Load"); + load_settings_dialog->exec(); + + if (load_settings_dialog->result() == QDialog::Rejected) { + return; } + mdiArea->closeAllSubWindows(); } template @@ -411,31 +412,26 @@ void MainWindow::saveSettings() const auto plugin_list = std::any_cast>(loaded_plugins_query.getParam("plugins")); for (const auto& entry : plugin_list) { widget_name = QString::fromStdString(entry->getName()); - userprefs.beginGroup(widget_name); - for (const auto& plugin : entry.second) { - userprefs.setValue("library", QString::fromStdString(plugin->getLibrary())); - userprefs.beginGroup(QString::number(widget_count)); - for (const auto& param_info : plugin->getComponentParametersInfo()) { - userprefs.setValue( - QString::fromStdString(param_info.name), - std::visit(overload {[](const int64_t& val) -> QString - { return QString::number(val); }, - [](const double& val) -> QString - { return QString::number(val); }, - [](const uint64_t& val) -> QString - { return QString::number(val); }, - [](const std::string& val) -> QString - { return QString::fromStdString(val); }, - [](const RT::State::state_t& val) -> QString { - return QString::number( - static_cast(val)); - }}, - param_info.value)); - } - userprefs.endGroup(); - widget_count++; + userprefs.beginGroup(QString::number(widget_count++)); + userprefs.setValue("library", QString::fromStdString(entry->getLibrary())); + for (const auto& param_info : entry->getComponentParametersInfo()) { + userprefs.setValue( + QString::fromStdString(param_info.name), + std::visit(overload {[](const int64_t& val) -> QString + { return QString::number(val); }, + [](const double& val) -> QString + { return QString::number(val); }, + [](const uint64_t& val) -> QString + { return QString::number(val); }, + [](const std::string& val) -> QString + { return QString::fromStdString(val); }, + [](const RT::State::state_t& val) -> QString { + return QString::number( + static_cast(val)); + }}, + param_info.value)); } - userprefs.endGroup(); + userprefs.endGroup(); //widget count } userprefs.endGroup(); // Widgets @@ -447,9 +443,7 @@ void MainWindow::saveSettings() void MainWindow::resetSettings() { - // systemMenu->clear(); - // mdiArea->closeAllSubWindows(); - // Settings::Manager::getInstance()->load("/usr/local/share/rtxi/rtxi.conf"); + mdiArea->closeAllSubWindows(); } void MainWindow::utilitiesMenuActivated(QAction* id) diff --git a/src/widgets.cpp b/src/widgets.cpp index 025e0ba92..2d021c1b3 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -558,7 +558,7 @@ RT::State::state_t Widgets::Plugin::getComponentState() } std::vector -Widgets::Plugin::getComponentParametersInfo() +Widgets::Plugin::getComponentParametersInfo() const { return this->plugin_component->getParametersInfo(); } diff --git a/src/widgets.hpp b/src/widgets.hpp index f5825f8ee..20deea71c 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -653,7 +653,7 @@ class Plugin : public Event::Handler * \return A vector of Widgets::Variable::Info representing parameter * information */ - virtual std::vector getComponentParametersInfo(); + std::vector getComponentParametersInfo() const; /*! * In some cases we need to know whether a component has been attached From 41a9f895637efffce5fba6d5779bdec6b5a11a97 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Tue, 9 Apr 2024 11:07:53 -0400 Subject: [PATCH 09/36] more updates to settings logic --- src/main_window.cpp | 93 +++++++++++++++++++++++++++++++-------------- src/widgets.cpp | 4 +- 2 files changed, 67 insertions(+), 30 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index 5d347480f..6480e8a47 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -352,6 +352,14 @@ void MainWindow::loadWindow() show(); } +template +struct overload : Ts... +{ + using Ts::operator()...; +}; +template +overload(Ts...) -> overload; + void MainWindow::loadSettings() { QSettings userprefs; @@ -365,18 +373,38 @@ void MainWindow::loadSettings() load_settings_dialog->exec(); if (load_settings_dialog->result() == QDialog::Rejected) { - return; + userprefs.endGroup(); + return; } + const QString profile = load_settings_dialog->textValue(); mdiArea->closeAllSubWindows(); + userprefs.beginGroup(profile); + const auto period = + userprefs.value("period", QVariant::fromValue(RT::OS::DEFAULT_PERIOD)) + .value(); + Event::Object event(Event::Type::RT_PERIOD_EVENT); + event.setParam("period", std::any(period)); + this->event_manager->postEvent(&event); + + userprefs.beginGroup("Widgets"); + QString plugin_name; + for(const auto& plugin_instance_id : userprefs.childGroups()){ + userprefs.beginGroup(plugin_instance_id); + plugin_name = userprefs.value("library").value(); + Event::Object plugin_insert_event(Event::Type::PLUGIN_INSERT_EVENT); + event.setParam("pluginName", std::any(plugin_name.toStdString())); + this->event_manager->postEvent(&plugin_insert_event); + for(const auto& variable_info : userprefs.childGroups()){ + + } + userprefs.endGroup(); // plugin_instance_id + } + + userprefs.endGroup(); // profile + userprefs.endGroup(); // widgets + userprefs.endGroup(); // workspaces } -template -struct overload : Ts... -{ - using Ts::operator()...; -}; -template -overload(Ts...) -> overload; void MainWindow::saveSettings() { QSettings userprefs; @@ -390,13 +418,16 @@ void MainWindow::saveSettings() save_settings_dialog->exec(); const QString profile_name = save_settings_dialog->textValue(); - if(userprefs.childGroups().contains(profile_name)) { userprefs.remove(profile_name); } + if (userprefs.childGroups().contains(profile_name)) { + userprefs.remove(profile_name); + } userprefs.beginGroup(profile_name); // get period and save Event::Object get_period_event(Event::Type::RT_GET_PERIOD_EVENT); event_manager->postEvent(&get_period_event); - const auto period = std::any_cast(get_period_event.getParam("period")); + const auto period = + std::any_cast(get_period_event.getParam("period")); userprefs.setValue("period", QString::number(period)); // Safe DAQ userprefs @@ -409,7 +440,8 @@ void MainWindow::saveSettings() int widget_count = 0; Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); this->event_manager->postEvent(&loaded_plugins_query); - const auto plugin_list = std::any_cast>(loaded_plugins_query.getParam("plugins")); + const auto plugin_list = std::any_cast>( + loaded_plugins_query.getParam("plugins")); for (const auto& entry : plugin_list) { widget_name = QString::fromStdString(entry->getName()); userprefs.beginGroup(QString::number(widget_count++)); @@ -417,33 +449,36 @@ void MainWindow::saveSettings() for (const auto& param_info : entry->getComponentParametersInfo()) { userprefs.setValue( QString::fromStdString(param_info.name), - std::visit(overload {[](const int64_t& val) -> QString - { return QString::number(val); }, - [](const double& val) -> QString - { return QString::number(val); }, - [](const uint64_t& val) -> QString - { return QString::number(val); }, - [](const std::string& val) -> QString - { return QString::fromStdString(val); }, - [](const RT::State::state_t& val) -> QString { - return QString::number( - static_cast(val)); - }}, - param_info.value)); + std::visit( + overload {[](const int64_t& val) -> QString + { return QString::number(val); }, + [](const double& val) -> QString + { return QString::number(val); }, + [](const uint64_t& val) -> QString + { return QString::number(val); }, + [](const std::string& val) -> QString + { return QString::fromStdString(val); }, + [](const RT::State::state_t& val) -> QString + { return QString::number(static_cast(val)); }}, + param_info.value)); } - userprefs.endGroup(); //widget count + userprefs.endGroup(); // widget count } - userprefs.endGroup(); // Widgets + userprefs.endGroup(); // Widgets userprefs.beginGroup("Connections"); - userprefs.endGroup(); // Connections - userprefs.endGroup(); // profile - userprefs.endGroup(); // Workspaces + userprefs.endGroup(); // Connections + userprefs.endGroup(); // profile + userprefs.endGroup(); // Workspaces } void MainWindow::resetSettings() { mdiArea->closeAllSubWindows(); + // reset period to default + Event::Object set_period_event(Event::Type::RT_PERIOD_EVENT); + set_period_event.setParam("period", std::any(RT::OS::DEFAULT_PERIOD)); + event_manager->postEvent(&set_period_event); } void MainWindow::utilitiesMenuActivated(QAction* id) diff --git a/src/widgets.cpp b/src/widgets.cpp index 2d021c1b3..91c41d060 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -560,7 +560,9 @@ RT::State::state_t Widgets::Plugin::getComponentState() std::vector Widgets::Plugin::getComponentParametersInfo() const { - return this->plugin_component->getParametersInfo(); + return plugin_component == nullptr + ? std::vector({}) + : this->plugin_component->getParametersInfo(); } void Widgets::Plugin::attachComponent( From 4706dc0ee4af14f1fa73f838e675d44e7a8f029c Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 15 Apr 2024 12:55:00 -0400 Subject: [PATCH 10/36] Fixed bug where incorrect use of string would add a null-terminated character at incorrect locations inside NIDAQ RTXI driver --- src/nidaq_driver.cpp | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/src/nidaq_driver.cpp b/src/nidaq_driver.cpp index 5c570323e..f71ab6551 100644 --- a/src/nidaq_driver.cpp +++ b/src/nidaq_driver.cpp @@ -174,23 +174,21 @@ inline void printError(int32_t status) ERROR_MSG("Unable to get code message"); return; } - std::string err_str(static_cast(error_size), '\0'); + std::vector err_buff(static_cast(error_size)); const int32_t errcode = DAQmxGetErrorString( - status, err_str.data(), static_cast(error_size)); + status, err_buff.data(), static_cast(error_size)); if (errcode < 0) { ERROR_MSG("Unable to parse message"); return; } - ERROR_MSG("Message : {}", err_str); + ERROR_MSG("Message : {}", std::string(err_buff.data())); } inline std::string physical_card_name(const std::string& device_name) { - const int32_t err = DAQmxGetDevProductType(device_name.c_str(), nullptr, 0); - std::string result(static_cast(err), '\0'); - DAQmxGetDevProductType( - device_name.c_str(), result.data(), static_cast(result.size())); - return result; + std::array buffer{}; + DAQmxGetDevProductType(device_name.c_str(), buffer.data(), 1024); + return std::string{buffer.data()}; } struct physical_channel_t @@ -982,10 +980,10 @@ void Driver::loadDevices() return; } const std::string alpha = "abcdefghijklmnopqrstuvwxyz"; - std::string string_buffer(static_cast(device_names_buffer_size), - '\0'); - DAQmxGetSysDevNames(string_buffer.data(), - static_cast(string_buffer.size())); + std::vector buffer(static_cast(device_names_buffer_size)); + DAQmxGetSysDevNames(buffer.data(), + static_cast(buffer.size())); + std::string string_buffer(buffer.data()); const std::vector device_names = split_string(string_buffer, ", "); std::vector channels; From a6af402de8c72308307b04cf7bebbaa05e9cc774 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 15 Apr 2024 13:52:02 -0400 Subject: [PATCH 11/36] Show actual buffer size for oscilloscope plots. Minor formatting --- plugins/oscilloscope/oscilloscope.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/plugins/oscilloscope/oscilloscope.cpp b/plugins/oscilloscope/oscilloscope.cpp index 8b7957d65..35881333e 100644 --- a/plugins/oscilloscope/oscilloscope.cpp +++ b/plugins/oscilloscope/oscilloscope.cpp @@ -223,7 +223,8 @@ void Oscilloscope::Panel::setActivity(IO::endpoint endpoint, bool activity) void Oscilloscope::Panel::applyChannelTab() { if (this->blocksListDropdown->count() <= 0 - || this->channelsList->count() <= 0) { + || this->channelsList->count() <= 0) + { return; } @@ -680,7 +681,8 @@ void Oscilloscope::Panel::showDisplayTab() trigThresh = 0; } else { while (fabs(trigThresh) < 1 - && trigThreshUnits < this->trigsThreshList->count()) { + && trigThreshUnits < this->trigsThreshList->count()) + { trigThresh *= 1000; ++trigThreshUnits; } @@ -688,7 +690,10 @@ void Oscilloscope::Panel::showDisplayTab() trigsThreshList->setCurrentIndex(trigThreshUnits); trigsThreshEdit->setText(QString::number(trigThresh)); - sizesEdit->setText(QString::number(scopeWindow->getDataSize())); + sizesEdit->setText( + QString::number(static_cast(scopeWindow->getDataSize() + * sizeof(Oscilloscope::sample)) + / 1e6)); } Oscilloscope::Panel::Panel(QMainWindow* mw, Event::Manager* ev_manager) From ab9d1776eeb40434aebd8b21943f7decb32fc6e6 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 15 Apr 2024 16:01:44 -0400 Subject: [PATCH 12/36] fix logger format for device update --- src/logger.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/logger.cpp b/src/logger.cpp index 900ddb0c4..9daea7173 100644 --- a/src/logger.cpp +++ b/src/logger.cpp @@ -119,7 +119,7 @@ void eventLogger::log(RT::Telemitry::Response response) this->ss << "System Threadlist Updated"; break; case RT::Telemitry::RT_DEVICE_LIST_UPDATE: - this->ss << " System Devicelist Updated"; + this->ss << "System Devicelist Updated"; break; case RT::Telemitry::RT_NOOP: this->ss << "NO-OP Acknowledged"; From 89094faff5bde4785de8373da3f9f974f7fa9204 Mon Sep 17 00:00:00 2001 From: Ivan F Valerio <36462302+fusge@users.noreply.github.com> Date: Wed, 17 Apr 2024 12:25:03 -0400 Subject: [PATCH 13/36] =?UTF-8?q?Simplified=20logic=20for=20task=20configu?= =?UTF-8?q?ration=20when=20enabling/disabling=20DAQ=20c=E2=80=A6=20(#167)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Simplified logic for task configuration when enabling/disabling DAQ channels. Fix channel order for activating channels. * Minor compile bugfix --- src/nidaq_driver.cpp | 73 +++++++++++++++++++++----------------------- 1 file changed, 34 insertions(+), 39 deletions(-) diff --git a/src/nidaq_driver.cpp b/src/nidaq_driver.cpp index f71ab6551..ea8ca019d 100644 --- a/src/nidaq_driver.cpp +++ b/src/nidaq_driver.cpp @@ -186,9 +186,9 @@ inline void printError(int32_t status) inline std::string physical_card_name(const std::string& device_name) { - std::array buffer{}; + std::array buffer {}; DAQmxGetDevProductType(device_name.c_str(), buffer.data(), 1024); - return std::string{buffer.data()}; + return std::string {buffer.data()}; } struct physical_channel_t @@ -494,45 +494,41 @@ int Device::setChannelActive(DAQ::ChannelType::type_t type, return 0; } DAQmxStopTask(task); - if (state) { - err = chan.addToTask(task); - chan.active = err == 0; - } else { - chan.active = false; - DAQmxClearTask(task); - err = DAQmxCreateTask(DAQ::ChannelType::type2string(type).c_str(), &task); - switch (type) { - case DAQ::ChannelType::AI: - case DAQ::ChannelType::DI: - DAQmxCfgInputBuffer(task, 1); - DAQmxSetReadOverWrite(task, DAQmx_Val_OverwriteUnreadSamps); - break; - case DAQ::ChannelType::AO: - case DAQ::ChannelType::DO: - DAQmxCfgOutputBuffer(task, 1); - break; - default: - break; + chan.active = state; + DAQmxClearTask(task); + err = DAQmxCreateTask(DAQ::ChannelType::type2string(type).c_str(), &task); + if (err != 0) { + printError(err); + for (auto& channel : physical_channels_registry.at(type)) { + channel.active = false; } - if (err != 0) { - for (auto& channel : physical_channels_registry.at(type)) { - channel.active = false; - } - active_channels.at(type).clear(); - return err; + active_channels.at(type).clear(); + return err; + } + switch (type) { + case DAQ::ChannelType::AI: + case DAQ::ChannelType::DI: + DAQmxCfgInputBuffer(task, 1); + DAQmxSetReadOverWrite(task, DAQmx_Val_OverwriteUnreadSamps); + break; + case DAQ::ChannelType::AO: + case DAQ::ChannelType::DO: + DAQmxCfgOutputBuffer(task, 1); + break; + default: + break; + } + for (auto& channel : physical_channels_registry.at(type)) { + if (!channel.active) { + continue; } - for (const auto& channel : physical_channels_registry.at(type)) { - if (!channel.active) { - continue; - } - err = channel.addToTask(task); - if (err != 0) { - break; - } + err = channel.addToTask(task); + if (err != 0) { + printError(err); + channel.active = false; } } - printError(err); - // active channels is an optimization for faster reading/writing in realtime. + // active_channels is an optimization for faster reading/writing in realtime. active_channels.at(type).clear(); for (auto& channel : physical_channels_registry.at(type)) { if (channel.active) { @@ -981,8 +977,7 @@ void Driver::loadDevices() } const std::string alpha = "abcdefghijklmnopqrstuvwxyz"; std::vector buffer(static_cast(device_names_buffer_size)); - DAQmxGetSysDevNames(buffer.data(), - static_cast(buffer.size())); + DAQmxGetSysDevNames(buffer.data(), static_cast(buffer.size())); std::string string_buffer(buffer.data()); const std::vector device_names = split_string(string_buffer, ", "); From 687cfbee4da5b8a29b6305d3e39c9d2036a7ff23 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 19 Apr 2024 13:08:35 -0400 Subject: [PATCH 14/36] Fixes bug where two plugins with the same name and output channel get recorder in the same dataset inside HDF5 file --- plugins/data_recorder/data_recorder.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/plugins/data_recorder/data_recorder.cpp b/plugins/data_recorder/data_recorder.cpp index c9abf20e7..d9e6a30ec 100644 --- a/plugins/data_recorder/data_recorder.cpp +++ b/plugins/data_recorder/data_recorder.cpp @@ -764,7 +764,9 @@ int DataRecorder::Plugin::create_component(IO::endpoint endpoint) return 0; } DataRecorder::record_channel chan; - chan.name = endpoint.block->getName(); + chan.name = std::to_string(endpoint.block->getID()); + chan.name += " "; + chan.name += endpoint.block->getName(); chan.name += " "; chan.name += endpoint.direction == IO::INPUT ? "INPUT" : "OUTPUT"; chan.name += " "; From 1d023eb9100a2569e9038511f5b251cef92a6dab Mon Sep 17 00:00:00 2001 From: Ivan F Valerio <36462302+fusge@users.noreply.github.com> Date: Fri, 26 Apr 2024 11:47:18 -0400 Subject: [PATCH 15/36] Update/generators (#169) * Major work updating biphase, mono, saw, and whitenoise generators to avoid allocations and improve realtime performance * Removed bugs from generators and maintained backwards compatibility * Fixed incorrect implementation of sawtooth and monophase generators --- libs/gen/gen_biphase.cpp | 78 +++++++++----------------- libs/gen/gen_biphase.h | 11 ++-- libs/gen/gen_mono.cpp | 69 +++++++++-------------- libs/gen/gen_mono.h | 11 ++-- libs/gen/gen_saw.cpp | 79 +++++++++----------------- libs/gen/gen_saw.h | 14 +++-- libs/gen/gen_sine.cpp | 49 ++++++---------- libs/gen/gen_sine.h | 9 +-- libs/gen/gen_whitenoise.cpp | 109 +++++++++++++++++------------------- libs/gen/gen_whitenoise.h | 40 ++++++------- libs/gen/gen_zap.cpp | 67 ++++++++++------------ libs/gen/gen_zap.h | 14 +++-- libs/gen/generator.cpp | 87 ---------------------------- libs/gen/generator.h | 51 ++++++----------- 14 files changed, 252 insertions(+), 436 deletions(-) delete mode 100644 libs/gen/generator.cpp diff --git a/libs/gen/gen_biphase.cpp b/libs/gen/gen_biphase.cpp index feb3e8cfc..64da9bd2f 100644 --- a/libs/gen/gen_biphase.cpp +++ b/libs/gen/gen_biphase.cpp @@ -16,68 +16,44 @@ */ #include "gen_biphase.h" - -// default constructor +#include GeneratorBiphase::GeneratorBiphase() - : width(1) - , amplitude(1) - , delay(1) + : m_width(1) + , m_amplitude(1) + , m_delay(1) { - dt = 1e-3; - numsamples = floor(delay / dt) + 2 * floor(width / dt) + 1; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(amplitude); // positive part - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(-amplitude); // negative part - } - numsamples = wave.size(); - index = 0; + setDeltaTime(1e-3); } -GeneratorBiphase::GeneratorBiphase(double delay, double width, double amplitude, +GeneratorBiphase::GeneratorBiphase(double delay, + double width, + double amplitude, double dt) - : Generator() + : m_width(width) + , m_amplitude(amplitude) + , m_delay(delay) { - numsamples = floor(delay / dt) + 2 * floor(width / dt) + 1; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(amplitude); // positive part - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(-amplitude); // negative part - } - numsamples = wave.size(); - index = 0; + setDeltaTime(dt); } -GeneratorBiphase::~GeneratorBiphase() +void GeneratorBiphase::init(double delay, + double width, + double amplitude, + double dt) { + m_delay = delay; + m_width = width; + m_amplitude = amplitude; + setDeltaTime(dt); + setIndex(0); } -void -GeneratorBiphase::init(double delay, double width, double amplitude, double dt) +double GeneratorBiphase::get() { - numsamples = floor(delay / dt) + 2 * floor(width / dt) + 1; - wave.clear(); - - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(amplitude); // positive part - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(-amplitude); // negative part - } - numsamples = wave.size(); - index = 0; + const double time = getIndex() * getDeltaTime() - m_delay; + getIndex()++; + if(time < 0.0) { return 0.0; } + const int sign = std::fmod(time,m_width) < m_width/2 ? 1 : -1; + return m_amplitude * sign; } diff --git a/libs/gen/gen_biphase.h b/libs/gen/gen_biphase.h index f562a6441..24fea6467 100644 --- a/libs/gen/gen_biphase.h +++ b/libs/gen/gen_biphase.h @@ -27,15 +27,16 @@ class GeneratorBiphase : public Generator // default constructor GeneratorBiphase(); GeneratorBiphase(double delay, double width, double amplitude, double dt); - ~GeneratorBiphase(); // initialize waveform void init(double delay, double width, double amplitude, double dt); -protected: - double width; // s - double amplitude; - double delay; // s + double get() override; + +private: + double m_width; // s + double m_amplitude; + double m_delay; // s }; #endif /* GEN_BIPHASE_H_ */ diff --git a/libs/gen/gen_mono.cpp b/libs/gen/gen_mono.cpp index 730602adc..4c4e9f269 100644 --- a/libs/gen/gen_mono.cpp +++ b/libs/gen/gen_mono.cpp @@ -15,59 +15,46 @@ * this program. If not, see . */ -#include "gen_mono.h" +#include -// default constructor +#include "gen_mono.h" GeneratorMono::GeneratorMono() - : delay(1) - , width(1) - , amplitude(1) + : m_delay(1) + , m_width(1) + , m_amplitude(1) { - dt = 1e-3; - numsamples = floor(delay / dt) + 2 * floor(width / dt) + 1; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(amplitude); // positive part - } - numsamples = wave.size(); - index = 0; + setDeltaTime(1e-3); } -GeneratorMono::GeneratorMono(double delay, double width, double amplitude, +GeneratorMono::GeneratorMono(double delay, + double width, + double amplitude, double dt) - : Generator() + : m_delay(delay) + , m_width(width) + , m_amplitude(amplitude) + { - numsamples = floor(delay / dt) + 2 * floor(width / dt) + 1; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(amplitude); // positive part - } - numsamples = wave.size(); - index = 0; + setDeltaTime(dt); } -GeneratorMono::~GeneratorMono() +void GeneratorMono::init(double delay, + double width, + double amplitude, + double dt) { + m_delay = delay; + m_width = width; + m_amplitude = amplitude; + setDeltaTime(dt); + setIndex(0); } -void -GeneratorMono::init(double delay, double width, double amplitude, double dt) +double GeneratorMono::get() { - numsamples = floor(delay / dt) + 2 * floor(width / dt) + 1; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - for (int i = 0; i < floor(width / dt); i++) { - wave.push_back(amplitude); // positive part - } - numsamples = wave.size(); - index = 0; + const double time = getIndex() * getDeltaTime(); + getIndex()++; + return m_amplitude + * static_cast(std::fmod(time, m_width + m_delay) > m_delay); } diff --git a/libs/gen/gen_mono.h b/libs/gen/gen_mono.h index bbe4ae5c1..28108b762 100644 --- a/libs/gen/gen_mono.h +++ b/libs/gen/gen_mono.h @@ -27,15 +27,16 @@ class GeneratorMono : public Generator // default constructor GeneratorMono(); GeneratorMono(double delay, double width, double amplitude, double dt); - ~GeneratorMono(); // initialize waveform void init(double delay, double width, double amplitude, double dt); -protected: - double delay; // s - double width; // s - double amplitude; + double get() override; + +private: + double m_delay; // s + double m_width; // s + double m_amplitude; }; #endif /* GEN_MONO_H_ */ diff --git a/libs/gen/gen_saw.cpp b/libs/gen/gen_saw.cpp index 405a3f3f8..a525c3cd3 100644 --- a/libs/gen/gen_saw.cpp +++ b/libs/gen/gen_saw.cpp @@ -15,72 +15,49 @@ * this program. If not, see . */ +#include + #include "gen_saw.h" // default constructor GeneratorSaw::GeneratorSaw() - : delay(1) - , width(1) - , amplitude(1) + : m_delay(1) + , m_width(1) + , m_amplitude(1) + , slope(2 * m_amplitude / m_width) { - dt = 1e-3; - numsamples = floor(width / 2 / dt) + 1; - double inc = amplitude / numsamples; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - while (wave.back() < amplitude) { - wave.push_back(wave.back() + inc); // up - } - while (wave.back() > 0) { - wave.push_back(wave.back() - inc); // down - } - numsamples = wave.size(); - index = 0; + setDeltaTime(1e-3); } -GeneratorSaw::GeneratorSaw(double delay, double width, double amplitude, +GeneratorSaw::GeneratorSaw(double delay, + double width, + double amplitude, double dt) - : Generator() + : m_delay(delay) + , m_width(width) + , m_amplitude(amplitude), slope(2 * m_amplitude / m_width) + { - numsamples = floor(width / 2 / dt) + 1; - double inc = amplitude / numsamples; - wave.clear(); - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - while (wave.back() < amplitude) { - wave.push_back(wave.back() + inc); // up - } - while (wave.back() > 0) { - wave.push_back(wave.back() - inc); // down - } - numsamples = wave.size(); - index = 0; + setDeltaTime(dt); } -GeneratorSaw::~GeneratorSaw() +void GeneratorSaw::init(double delay, double width, double amplitude, double dt) { + m_delay = delay; + m_width = width; + m_amplitude = amplitude; + setDeltaTime(dt); + setIndex(0); + slope = 2 * m_amplitude / m_width; } -void -GeneratorSaw::init(double delay, double width, double amplitude, double dt) +double GeneratorSaw::get() { - numsamples = floor(width / 2 / dt) + 1; - double inc = amplitude / numsamples; - wave.clear(); - - for (int i = 0; i < floor(delay / dt); i++) { - wave.push_back(0); // initial delay - } - while (wave.back() < amplitude) { - wave.push_back(wave.back() + inc); // up - } - while (wave.back() > 0) { - wave.push_back(wave.back() - inc); // down + const double time = fmod(getIndex() * getDeltaTime() - m_delay, m_width); + getIndex()++; + if (time < 0.0) { + return 0.0; } - numsamples = wave.size(); - index = 0; + return slope * time; } diff --git a/libs/gen/gen_saw.h b/libs/gen/gen_saw.h index 4e9ee7e13..2e0e20e4b 100644 --- a/libs/gen/gen_saw.h +++ b/libs/gen/gen_saw.h @@ -18,24 +18,26 @@ #ifndef GEN_SAW_H_ #define GEN_SAW_H_ +#include #include "generator.h" class GeneratorSaw : public Generator { - public: // default constructor GeneratorSaw(); GeneratorSaw(double delay, double width, double amplitude, double dt); - ~GeneratorSaw(); + + double get() override; // initialize waveform void init(double delay, double width, double amplitude, double dt); -protected: - double delay; // delay in time (s) between ramps - double width; // width in time (s) of ramp - double amplitude; +private: + double m_delay; + double m_width; + double m_amplitude; + double slope; }; #endif /* GEN_SAW_H_ */ diff --git a/libs/gen/gen_sine.cpp b/libs/gen/gen_sine.cpp index 398771b64..dcaf655b7 100644 --- a/libs/gen/gen_sine.cpp +++ b/libs/gen/gen_sine.cpp @@ -15,51 +15,36 @@ * this program. If not, see . */ +#include +#include #include "gen_sine.h" -#define TWOPI 6.28318531 - -// default constructor +constexpr double TWOPI = 2 * M_PI; GeneratorSine::GeneratorSine() - : freq(1) - , amplitude(1) + : m_freq(1) + , m_amplitude(1) { - index = 0; - dt = 1e-3; - numsamples = floor(1 / freq / dt); - wave.clear(); - for (int i = 0; i < numsamples; i++) { - wave.push_back(amplitude * sin(TWOPI * freq * i * dt)); - } - numsamples = wave.size(); - index = 0; + setDeltaTime(1e-3); } GeneratorSine::GeneratorSine(double freq, double amplitude, double dt) - : Generator() + : m_freq(freq) + , m_amplitude(amplitude) { - numsamples = floor(1 / freq / dt); - wave.clear(); - for (int i = 0; i < numsamples; i++) { - wave.push_back(amplitude * sin(TWOPI * freq * i * dt)); - } - numsamples = wave.size(); - index = 0; + setDeltaTime(dt); } -GeneratorSine::~GeneratorSine() +double GeneratorSine::get() { + return m_amplitude * gsl_sf_sin(TWOPI * m_freq * getDeltaTime() * getIndex()++); } -void -GeneratorSine::init(double freq, double amplitude, double dt) +void GeneratorSine::init(double freq, double amplitude, double dt) { - numsamples = floor(1 / freq / dt); - wave.clear(); - for (int i = 0; i < numsamples; i++) { - wave.push_back(amplitude * sin(TWOPI * freq * i * dt)); - } - numsamples = wave.size(); - index = 0; + m_freq = freq; + m_amplitude = amplitude; + setDeltaTime(dt); + setIndex(0); } + diff --git a/libs/gen/gen_sine.h b/libs/gen/gen_sine.h index f59c570c4..256f79dde 100644 --- a/libs/gen/gen_sine.h +++ b/libs/gen/gen_sine.h @@ -27,14 +27,15 @@ class GeneratorSine : public Generator // default constructor GeneratorSine(); GeneratorSine(double freq, double amplitude, double dt); - ~GeneratorSine(); + + double get() override; // initialize waveform void init(double freq, double amplitude, double dt); -protected: - double freq; // Hz - double amplitude; +private: + double m_freq; // Hz + double m_amplitude; }; #endif /* GEN_SINE_H_ */ diff --git a/libs/gen/gen_whitenoise.cpp b/libs/gen/gen_whitenoise.cpp index b4a0b6a5e..3fc78fb72 100644 --- a/libs/gen/gen_whitenoise.cpp +++ b/libs/gen/gen_whitenoise.cpp @@ -19,84 +19,79 @@ * Generates white noise using the Box-Muller method */ +#include +#include #include "gen_whitenoise.h" -// default constructor - -GeneratorWNoise::GeneratorWNoise() - : variance(1) +GeneratorWNoise::GeneratorWNoise(double variance) + : m_variance(variance) + , range_type(gsl_rng_default) + , random_number_generator(gsl_rng_alloc(range_type)) { - numsamples = 1; - wave.clear(); - gsl_rng_env_setup(); // get default generator type and random seed - T = gsl_rng_default; // mt - r = gsl_rng_alloc(T); // default seed = 0 - - for (int i = 0; i < numsamples; i++) { - wave.push_back(gsl_ran_gaussian(r, sqrt(variance))); - } + gsl_rng_set(random_number_generator, m_seed); +} - numsamples = wave.size(); - index = 0; - genstate = gsl_rng_clone(r); - gsl_rng_free(r); +GeneratorWNoise::GeneratorWNoise(const GeneratorWNoise& gen) + : Generator(gen) +{ + if(this == &gen) { return; } + m_variance = gen.m_variance; + m_seed = gen.m_seed; + range_type = gen.range_type; + random_number_generator = gsl_rng_clone(gen.random_number_generator); } -GeneratorWNoise::GeneratorWNoise(double variance) - : Generator() +GeneratorWNoise::GeneratorWNoise(GeneratorWNoise&& gen) noexcept + : m_variance(1.0) { - numsamples = 1; - wave.clear(); - gsl_rng_env_setup(); // get default generator type and random seed - T = gsl_rng_default; // mt - r = gsl_rng_alloc(T); // default seed = 0 + if(this == &gen) { return; } + std::swap(m_variance, gen.m_variance); + std::swap(m_seed, gen.m_seed); + range_type = gen.range_type; + std::swap(random_number_generator, gen.random_number_generator); +} - for (int i = 0; i < numsamples; i++) { - wave.push_back(gsl_ran_gaussian(r, sqrt(variance))); - } +GeneratorWNoise& GeneratorWNoise::operator=(const GeneratorWNoise& gen) +{ + if(this == &gen) { return *this; } + m_variance = gen.m_variance; + m_seed = gen.m_seed; + range_type = gen.range_type; + random_number_generator = gsl_rng_clone(gen.random_number_generator); + return *this; +} - numsamples = wave.size(); - index = 0; - genstate = gsl_rng_clone(r); - gsl_rng_free(r); +GeneratorWNoise& GeneratorWNoise::operator=(GeneratorWNoise&& gen) noexcept +{ + if(this == &gen) { return *this; } + std::swap(m_variance, gen.m_variance); + std::swap(m_seed, gen.m_seed); + range_type = gen.range_type; + std::swap(random_number_generator, gen.random_number_generator); + return *this; } GeneratorWNoise::~GeneratorWNoise() { + gsl_rng_free(random_number_generator); } -void -GeneratorWNoise::init(double variance) +void GeneratorWNoise::init(uint64_t seed) { - numsamples = 1; - wave.clear(); - r = gsl_rng_alloc(T); // default seed = 0 - gsl_rng_memcpy(r, genstate); - - for (int i = 0; i < numsamples; i++) { - wave.push_back(gsl_ran_gaussian(r, sqrt(variance))); - } + gsl_rng_set(random_number_generator, seed); +} - numsamples = wave.size(); - index = 0; - gsl_rng_memcpy(genstate, r); - gsl_rng_free(r); +double GeneratorWNoise::get() +{ + return gsl_ran_gaussian(random_number_generator, sqrt(m_variance)); } -double -GeneratorWNoise::get() +void GeneratorWNoise::setVariance(double var) { - double value = wave[index]; - index++; - if (index >= numsamples) { - index = 0; - init(variance); - } - return value; + m_variance = var; } -void -GeneratorWNoise::setVariance(double var) +double GeneratorWNoise::getVariance() const { - variance = var; + return m_variance; } diff --git a/libs/gen/gen_whitenoise.h b/libs/gen/gen_whitenoise.h index 9d55aa43f..cfcb4ce66 100644 --- a/libs/gen/gen_whitenoise.h +++ b/libs/gen/gen_whitenoise.h @@ -18,37 +18,37 @@ #ifndef GEN_WHITENOISE_H_ #define GEN_WHITENOISE_H_ -#include "generator.h" +#include #include #include +#include "generator.h" class GeneratorWNoise : public Generator { public: - // default constructor - GeneratorWNoise(); - GeneratorWNoise(double variance); - ~GeneratorWNoise(); - // initialize waveform - void init(double variance); + explicit GeneratorWNoise(double variance=1.0); + GeneratorWNoise(const GeneratorWNoise& gen); + GeneratorWNoise(GeneratorWNoise&& gen) noexcept ; + GeneratorWNoise& operator=(const GeneratorWNoise&); + GeneratorWNoise& operator=(GeneratorWNoise&&) noexcept ; + ~GeneratorWNoise() override; + + void init(uint64_t seed); + // get readout - double get(); + double get() override; + // set the variance of the generator void setVariance(double var); -protected: - double variance; - double s; - double u1; - double u2; - double v1; - double v2; - double x; - double y; - const gsl_rng_type* T; - gsl_rng* r; - gsl_rng* genstate; + double getVariance() const; + +private: + double m_variance; + uint64_t m_seed = 0; + const gsl_rng_type* range_type; + gsl_rng* random_number_generator = nullptr; }; #endif /* GEN_WHITENOISE_H_ */ diff --git a/libs/gen/gen_zap.cpp b/libs/gen/gen_zap.cpp index a99a5efe2..2f230c81b 100644 --- a/libs/gen/gen_zap.cpp +++ b/libs/gen/gen_zap.cpp @@ -27,58 +27,49 @@ * frequency was varied from 20 to 0 or 40 to 10 Hz. */ +#include +#include #include "gen_zap.h" -#define TWOPI 6.28318531 +constexpr double TWOPI = 2 * M_PI; // default constructor GeneratorZap::GeneratorZap() - : freq(1) - , freq2(20) - , duration(10) - , amplitude(1) + : m_freq(1) + , m_freq2(20) + , m_duration(10) + , m_amplitude(1) { - index = 0; - dt = 1e-3; - numsamples = floor(duration / dt); - wave.clear(); - for (int i = 0; i < numsamples; i++) { - double freqtime = freq + (freq2 - freq) * (i * dt / duration); - wave.push_back(amplitude * sin(TWOPI * freqtime * i * dt)); - } - numsamples = wave.size(); - index = 0; + setDeltaTime(1e-3); } -GeneratorZap::GeneratorZap(double freq, double freq2, double amplitude, - double duration, double dt) - : Generator() +GeneratorZap::GeneratorZap( + double freq, double freq2, double amplitude, double duration, double dt) + : m_freq(freq) + , m_freq2(freq2) + , m_duration(duration) + , m_amplitude(amplitude) { - numsamples = floor(duration / dt); - wave.clear(); - for (int i = 0; i < numsamples; i++) { - double freqtime = freq + (freq2 - freq) * (i * dt / duration); - wave.push_back(amplitude * sin(TWOPI * freqtime * i * dt)); - } - numsamples = wave.size(); - index = 0; + setDeltaTime(dt); } -GeneratorZap::~GeneratorZap() +void GeneratorZap::init( + double freq, double freq2, double amplitude, double duration, double dt) { + setDeltaTime(dt); + m_freq = freq; + m_freq2 = freq2; + m_duration = duration; + m_amplitude = amplitude; + setIndex(0); } -void -GeneratorZap::init(double freq, double freq2, double amplitude, double duration, - double dt) +double GeneratorZap::get() { - numsamples = floor(duration / dt); - wave.clear(); - for (int i = 0; i < numsamples; i++) { - double freqtime = freq + (freq2 - freq) * (i * dt / duration); - wave.push_back(amplitude * sin(TWOPI * freqtime * i * dt)); - } - numsamples = wave.size(); - index = 0; + const double dt = getDeltaTime(); + if(getIndex() > m_duration / dt) { setIndex(0); } + const double freqtime = m_freq + (m_freq2 - m_freq) * ( getIndex() * dt / m_duration); + return m_amplitude * gsl_sf_sin(TWOPI * freqtime * dt * getIndex()++); } + diff --git a/libs/gen/gen_zap.h b/libs/gen/gen_zap.h index 94312e11e..e4adffb70 100644 --- a/libs/gen/gen_zap.h +++ b/libs/gen/gen_zap.h @@ -28,16 +28,18 @@ class GeneratorZap : public Generator GeneratorZap(); GeneratorZap(double freq, double freq2, double amplitude, double duration, double dt); - ~GeneratorZap(); + + double get() override; + // initialize waveform void init(double freq, double freq2, double amplitude, double duration, double dt); -protected: - double freq; // Hz - double freq2; - double duration; - double amplitude; +private: + double m_freq; // Hz + double m_freq2; + double m_duration; + double m_amplitude; }; #endif /* GEN_ZAP_H_ */ diff --git a/libs/gen/generator.cpp b/libs/gen/generator.cpp deleted file mode 100644 index a957dc313..000000000 --- a/libs/gen/generator.cpp +++ /dev/null @@ -1,87 +0,0 @@ -/* - * Copyright (C) 2011 Georgia Institute of Technology - * - * This program is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the Free - * Software Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * This program is distributed in the hope that it will be useful, but WITHOUT - * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - * more details. - * - * You should have received a copy of the GNU General Public License along with - * this program. If not, see . - */ - -#include "generator.h" - -Generator::Generator() - : index(0) - , numsamples(1) - , dt(1e-3) -{ - wave.clear(); - wave.push_back(0); -} - -Generator::~Generator() -{ -} - -void -Generator::clear() -{ - wave.clear(); - wave.push_back(0); - index = 0; - numsamples = wave.size(); -} - -void -Generator::init() -{ - wave.clear(); - wave.push_back(0); - index = 0; - numsamples = wave.size(); -} - -double -Generator::get() -{ - double value = wave[index]; - index++; - if (index >= numsamples) - index = 0; - return value; -} - -double -Generator::getOne() -{ - double value = wave[index]; - index++; - if (index >= numsamples) - value = 0; - return value; -} - -int -Generator::numSamples() const -{ - return numsamples; -} - -int -Generator::getIndex() const -{ - return index; -} - -void -Generator::setIndex(int value) -{ - index = value; -} diff --git a/libs/gen/generator.h b/libs/gen/generator.h index 1a5ee453b..263988190 100644 --- a/libs/gen/generator.h +++ b/libs/gen/generator.h @@ -18,43 +18,28 @@ #ifndef GENERATOR_H_ #define GENERATOR_H_ -#include -#include - class Generator { public: - // default constructor - Generator(); - ~Generator(); - - // clear the waveform - void clear(); - - // initialize waveform - void init(); - - // get readout for continuous signal, repeating cycle - double get(); - - // get readout for single cycle - double getOne(); - - // get number of samples - int numSamples() const; - - // get current index for readout - int getIndex() const; - - // set index - void setIndex(int value); - -protected: - std::vector wave; - int index; - int numsamples; - double dt; + Generator() = default; + Generator(const Generator&) = default; + Generator(Generator&&) = default; + Generator& operator=(const Generator&) = default; + Generator& operator=(Generator&&) = default; + virtual ~Generator() = default; + + // get readout for random number generator + virtual double get() = 0; + + virtual void clear() { index = 0; } + void setIndex(int ind) { index = ind; } + int& getIndex() { return index; } + double getDeltaTime() const { return dt; } + void setDeltaTime(double delta) { dt = delta; } +private: + double dt{}; + int index=0; }; #endif /* GENERATOR_H_ */ From f32befd6609d6cac987981f4b221c531ec483b66 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Wed, 8 May 2024 13:15:42 -0400 Subject: [PATCH 16/36] further updates to settings logic --- src/main_window.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index 6480e8a47..f8ef0f890 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -388,14 +388,19 @@ void MainWindow::loadSettings() userprefs.beginGroup("Widgets"); QString plugin_name; + + auto vartype=static_cast(Widgets::Variable::UNKNOWN); + std::variant value; for(const auto& plugin_instance_id : userprefs.childGroups()){ userprefs.beginGroup(plugin_instance_id); plugin_name = userprefs.value("library").value(); Event::Object plugin_insert_event(Event::Type::PLUGIN_INSERT_EVENT); event.setParam("pluginName", std::any(plugin_name.toStdString())); this->event_manager->postEvent(&plugin_insert_event); - for(const auto& variable_info : userprefs.childGroups()){ - + for(const auto& variable_id : userprefs.childGroups()){ + vartype = userprefs.value("type").value().toULong(); + if(userprefs.value( + userprefs.endGroup(); // variable info } userprefs.endGroup(); // plugin_instance_id } @@ -436,19 +441,18 @@ void MainWindow::saveSettings() // Safe Widget userprefs userprefs.beginGroup("Widgets"); - QString widget_name; int widget_count = 0; Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); this->event_manager->postEvent(&loaded_plugins_query); const auto plugin_list = std::any_cast>( loaded_plugins_query.getParam("plugins")); for (const auto& entry : plugin_list) { - widget_name = QString::fromStdString(entry->getName()); userprefs.beginGroup(QString::number(widget_count++)); userprefs.setValue("library", QString::fromStdString(entry->getLibrary())); for (const auto& param_info : entry->getComponentParametersInfo()) { + userprefs.setValue("type", QString::number(param_info.id)); userprefs.setValue( - QString::fromStdString(param_info.name), + QString::number(static_cast(param_info.vartype)), std::visit( overload {[](const int64_t& val) -> QString { return QString::number(val); }, From 6749723d7d2cce6e0a496a4cf71511108433adcc Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 10 May 2024 15:12:54 -0400 Subject: [PATCH 17/36] Improved resiliance by ignoring missing drivers/devices. Show error message and continue. --- src/workspace.cpp | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/src/workspace.cpp b/src/workspace.cpp index c0410e799..742838818 100644 --- a/src/workspace.cpp +++ b/src/workspace.cpp @@ -58,13 +58,21 @@ Workspace::Manager::Manager(Event::Manager* ev_manager) const QDir bin_dir = QCoreApplication::applicationDirPath(); const std::string nidaq_driver_name = "librtxinidaqdriver.so"; if (bin_dir.exists(QString::fromStdString(nidaq_driver_name))) { - this->registerDriver(bin_dir.path().toStdString() + std::string("/") - + nidaq_driver_name); + try{ + this->registerDriver(bin_dir.path().toStdString() + std::string("/") + + nidaq_driver_name); + } catch (std::runtime_error& exception){ + ERROR_MSG("Unable to load NIDAQ rtxi driver"); + } } const std::string gsc_driver_name = "librtxi_gsc16aio168_driver.so"; if (bin_dir.exists(QString::fromStdString(gsc_driver_name))) { - this->registerDriver(bin_dir.path().toStdString() + std::string("/") - + gsc_driver_name); + try { + this->registerDriver(bin_dir.path().toStdString() + std::string("/") + + gsc_driver_name); + } catch (std::runtime_error& excepttion){ + ERROR_MSG("Unable to load GSC aio168 rtxi driver"); + } } } From 470c7fc28ae430a76834fcdcd18f7018ac76d986 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 24 May 2024 13:49:43 -0400 Subject: [PATCH 18/36] ubuntu has issues with building rtxi with apt cmake instead of snap cmake. Tell install script to install snap version instead --- scripts/install_dependencies.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/scripts/install_dependencies.sh b/scripts/install_dependencies.sh index 82ad0f375..084136064 100755 --- a/scripts/install_dependencies.sh +++ b/scripts/install_dependencies.sh @@ -37,8 +37,9 @@ apt-get -y install \ build-essential qtbase5-dev qtbase5-dev-tools \ libqwt-qt5-dev libqt5svg5-dev libhdf5-dev \ libgsl-dev libgtest-dev libgmock-dev libfmt-dev vim lshw stress \ - binutils-dev zstd git cmake \ + binutils-dev zstd git \ crash kexec-tools makedumpfile kernel-wedge libncurses5-dev libelf-dev \ flex bison pkgconf python3-pip ninja-build dwarves +snap install cmake echo "-----> Package dependencies installed." echo "-----> Done." From f7671189e4eb904350670791be6d1efb62669d30 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Tue, 16 Jul 2024 00:44:09 -0400 Subject: [PATCH 19/36] Finalizing changes to settings load/save --- src/main_window.cpp | 50 +++++++++++---------------------------------- src/widgets.cpp | 35 +++++++++++++++++++++++++++++++ src/widgets.hpp | 7 +++++++ 3 files changed, 54 insertions(+), 38 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index f8ef0f890..644058ced 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -352,14 +352,6 @@ void MainWindow::loadWindow() show(); } -template -struct overload : Ts... -{ - using Ts::operator()...; -}; -template -overload(Ts...) -> overload; - void MainWindow::loadSettings() { QSettings userprefs; @@ -389,25 +381,24 @@ void MainWindow::loadSettings() userprefs.beginGroup("Widgets"); QString plugin_name; - auto vartype=static_cast(Widgets::Variable::UNKNOWN); + auto vartype = static_cast(Widgets::Variable::UNKNOWN); std::variant value; - for(const auto& plugin_instance_id : userprefs.childGroups()){ + Widgets::Plugin* plugin_ptr=nullptr; + for (const auto& plugin_instance_id : userprefs.childGroups()) { userprefs.beginGroup(plugin_instance_id); - plugin_name = userprefs.value("library").value(); + plugin_name = userprefs.value("library").value(); Event::Object plugin_insert_event(Event::Type::PLUGIN_INSERT_EVENT); event.setParam("pluginName", std::any(plugin_name.toStdString())); this->event_manager->postEvent(&plugin_insert_event); - for(const auto& variable_id : userprefs.childGroups()){ - vartype = userprefs.value("type").value().toULong(); - if(userprefs.value( - userprefs.endGroup(); // variable info - } - userprefs.endGroup(); // plugin_instance_id + // Load the settings + plugin_ptr = std::any_cast(event.getParam("pluginPointer")); + plugin_ptr->loadParameterSettings(userprefs); + userprefs.endGroup(); // plugin_instance_id } - userprefs.endGroup(); // profile - userprefs.endGroup(); // widgets - userprefs.endGroup(); // workspaces + userprefs.endGroup(); // profile + userprefs.endGroup(); // widgets + userprefs.endGroup(); // workspaces } void MainWindow::saveSettings() @@ -448,24 +439,7 @@ void MainWindow::saveSettings() loaded_plugins_query.getParam("plugins")); for (const auto& entry : plugin_list) { userprefs.beginGroup(QString::number(widget_count++)); - userprefs.setValue("library", QString::fromStdString(entry->getLibrary())); - for (const auto& param_info : entry->getComponentParametersInfo()) { - userprefs.setValue("type", QString::number(param_info.id)); - userprefs.setValue( - QString::number(static_cast(param_info.vartype)), - std::visit( - overload {[](const int64_t& val) -> QString - { return QString::number(val); }, - [](const double& val) -> QString - { return QString::number(val); }, - [](const uint64_t& val) -> QString - { return QString::number(val); }, - [](const std::string& val) -> QString - { return QString::fromStdString(val); }, - [](const RT::State::state_t& val) -> QString - { return QString::number(static_cast(val)); }}, - param_info.value)); - } + entry->saveParameterSettings(userprefs); userprefs.endGroup(); // widget count } userprefs.endGroup(); // Widgets diff --git a/src/widgets.cpp b/src/widgets.cpp index 91c41d060..55c8ef334 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include #include #include @@ -659,3 +660,37 @@ Widgets::Panel* Widgets::Plugin::getPanel() { return this->widget_panel; } + +// Helper definitions for visitor pattern with std::visit +template +struct overload : Ts... +{ + using Ts::operator()...; +}; +template +overload(Ts...) -> overload; + +void Widgets::Plugin::loadParameterSettings(QSettings& userprefs) {} + +void Widgets::Plugin::saveParameterSettings(QSettings& userprefs) const +{ + userprefs.setValue("library", QString::fromStdString(this->getLibrary())); + for (const auto& param_info : this->getComponentParametersInfo()) { + userprefs.beginGroup("standardParams"); + userprefs.setValue( + QString::number(static_cast(param_info.id)), + std::visit(overload {[](const int64_t& val) -> QString + { return QString::number(val); }, + [](const double& val) -> QString + { return QString::number(val); }, + [](const uint64_t& val) -> QString + { return QString::number(val); }, + [](const std::string& val) -> QString + { return QString::fromStdString(val); }, + [](const RT::State::state_t& val) -> QString { + return QString::number(static_cast(val)); + }}, + param_info.value)); + } + userprefs.endGroup(); // standardParams +} diff --git a/src/widgets.hpp b/src/widgets.hpp index 20deea71c..4c53801e6 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -30,6 +30,7 @@ Q_DECLARE_METATYPE(IO::endpoint) Q_DECLARE_METATYPE(RT::block_connection_t) Q_DECLARE_METATYPE(RT::State::state_t) +class QSettings; /*! * Contains all the classes and structures relevant to Widgets */ @@ -274,6 +275,7 @@ class Component : public RT::Thread */ Widgets::Plugin* getHostPlugin() { return this->hostPlugin; } + private: std::vector parameters; Widgets::Plugin* hostPlugin; @@ -663,6 +665,11 @@ class Plugin : public Event::Handler */ bool hasComponent() { return plugin_component != nullptr; } + void loadParameterSettings(QSettings& userprefs); + virtual void loadCustomParameterSettings(QSettings& userprefs) {} + void saveParameterSettings(QSettings& userprefs) const ; + virtual void saveCustomParameterSettings(QSettings& userprefs) const {} + protected: Widgets::Component* getComponent(); Event::Manager* getEventManager(); From b5235541e7e438b7c5e13210ef9e39164682bb88 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 29 Jul 2024 22:01:16 -0400 Subject: [PATCH 20/36] Now have a working settings system that saves and loads RTXI parameters. WIP --- src/main_window.cpp | 32 ++++++++++++++++------ src/main_window.hpp | 8 ++++-- src/widgets.cpp | 67 +++++++++++++++++++++++++++------------------ src/widgets.hpp | 1 + 4 files changed, 71 insertions(+), 37 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index 644058ced..67d88d79a 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -380,19 +380,20 @@ void MainWindow::loadSettings() userprefs.beginGroup("Widgets"); QString plugin_name; - - auto vartype = static_cast(Widgets::Variable::UNKNOWN); std::variant value; - Widgets::Plugin* plugin_ptr=nullptr; + Widgets::Plugin* plugin_ptr = nullptr; + std::string event_status; for (const auto& plugin_instance_id : userprefs.childGroups()) { userprefs.beginGroup(plugin_instance_id); plugin_name = userprefs.value("library").value(); - Event::Object plugin_insert_event(Event::Type::PLUGIN_INSERT_EVENT); - event.setParam("pluginName", std::any(plugin_name.toStdString())); - this->event_manager->postEvent(&plugin_insert_event); + this->loadWidget(plugin_name, plugin_ptr); // Load the settings - plugin_ptr = std::any_cast(event.getParam("pluginPointer")); + userprefs.beginGroup("standardParams"); plugin_ptr->loadParameterSettings(userprefs); + userprefs.endGroup(); // standardParams + userprefs.beginGroup("customParams"); + plugin_ptr->loadCustomParameterSettings(userprefs); + userprefs.endGroup(); // customParams userprefs.endGroup(); // plugin_instance_id } @@ -439,13 +440,20 @@ void MainWindow::saveSettings() loaded_plugins_query.getParam("plugins")); for (const auto& entry : plugin_list) { userprefs.beginGroup(QString::number(widget_count++)); + userprefs.setValue("library", QString::fromStdString(entry->getLibrary())); + userprefs.beginGroup("standardParams"); entry->saveParameterSettings(userprefs); + userprefs.endGroup(); // standardParams + userprefs.beginGroup("customParams"); + entry->saveCustomParameterSettings(userprefs); + userprefs.endGroup(); // customParams userprefs.endGroup(); // widget count } userprefs.endGroup(); // Widgets userprefs.beginGroup("Connections"); userprefs.endGroup(); // Connections + userprefs.endGroup(); // profile userprefs.endGroup(); // Workspaces } @@ -466,6 +474,13 @@ void MainWindow::utilitiesMenuActivated(QAction* id) } void MainWindow::loadWidget(const QString& module_name) +{ + Widgets::Plugin* unused_pointer = nullptr; + this->loadWidget(module_name, unused_pointer); +} + +void MainWindow::loadWidget(const QString& module_name, + Widgets::Plugin*& rtxi_plugin_pointer) { Event::Object event(Event::Type::PLUGIN_INSERT_EVENT); event.setParam("pluginName", std::any(module_name.toStdString())); @@ -480,8 +495,7 @@ void MainWindow::loadWidget(const QString& module_name) auto create_rtxi_panel_func = std::any_cast( event.getParam("createRTXIPanel")); - auto* rtxi_plugin_pointer = - std::any_cast(event.getParam("pluginPointer")); + rtxi_plugin_pointer = std::any_cast(event.getParam("pluginPointer")); auto* rtxi_panel_pointer = create_rtxi_panel_func(this, this->event_manager); rtxi_plugin_pointer->attachPanel(rtxi_panel_pointer); // finally plugins can also receive events so make sure to register them diff --git a/src/main_window.hpp b/src/main_window.hpp index 1e72b1aab..ffa0cf359 100644 --- a/src/main_window.hpp +++ b/src/main_window.hpp @@ -28,11 +28,14 @@ #include #include #include - -#include +#include #include "event.hpp" +namespace Widgets{ +class Plugin; +} // namespace Widgets + class SaveSettingsDialog : public QDialog { public: @@ -161,6 +164,7 @@ private slots: private: void loadWidget(const QString& module_name); + void loadWidget(const QString& module_name, Widgets::Plugin*& rtxi_plugin_pointer); Event::Manager* event_manager; QMdiArea* mdiArea = nullptr; QList subWindows; diff --git a/src/widgets.cpp b/src/widgets.cpp index 55c8ef334..3f71686c0 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -17,6 +17,7 @@ #include #include "debug.hpp" +#include "event.hpp" std::string Widgets::Variable::state2string(RT::State::state_t state) { @@ -661,36 +662,50 @@ Widgets::Panel* Widgets::Plugin::getPanel() return this->widget_panel; } -// Helper definitions for visitor pattern with std::visit -template -struct overload : Ts... +void Widgets::Plugin::loadParameterSettings(QSettings& userprefs) { - using Ts::operator()...; -}; -template -overload(Ts...) -> overload; - -void Widgets::Plugin::loadParameterSettings(QSettings& userprefs) {} + QString id_str; + QVariant value; + for (const auto& param_info : this->getComponentParametersInfo()) { + id_str = QString::number(param_info.id); + value = userprefs.value(id_str); + if(!value.isValid()){ + ERROR_MSG("Widgets::Plugin::loadParameterSettings : The loaded setting for " + "parameter {} is not valid! skipping...", param_info.name); + continue; + } + // NOTE: Here we will assume that the type of the stored parameter matches the + // one stored inside the component. This may not be true in the future if the + // plugin developer decides to change the types of parameters. In this case, the + // QVariant will return 0 instead. + switch (param_info.vartype) { + case Widgets::Variable::INT_PARAMETER: + this->setComponentParameter( + param_info.id, + static_cast(userprefs.value(id_str).toInt())); + break; + case Variable::DOUBLE_PARAMETER: + this->setComponentParameter( + param_info.id, + static_cast(userprefs.value(id_str).toDouble())); + break; + case Variable::UINT_PARAMETER: + case Variable::STATE: + this->setComponentParameter( + param_info.id, + static_cast(userprefs.value(id_str).toUInt())); + break; + case Variable::COMMENT: + case Variable::UNKNOWN: + break; + } + } +} void Widgets::Plugin::saveParameterSettings(QSettings& userprefs) const { - userprefs.setValue("library", QString::fromStdString(this->getLibrary())); for (const auto& param_info : this->getComponentParametersInfo()) { - userprefs.beginGroup("standardParams"); - userprefs.setValue( - QString::number(static_cast(param_info.id)), - std::visit(overload {[](const int64_t& val) -> QString - { return QString::number(val); }, - [](const double& val) -> QString - { return QString::number(val); }, - [](const uint64_t& val) -> QString - { return QString::number(val); }, - [](const std::string& val) -> QString - { return QString::fromStdString(val); }, - [](const RT::State::state_t& val) -> QString { - return QString::number(static_cast(val)); - }}, - param_info.value)); + userprefs.setValue(QString::number(static_cast(param_info.id)), + QVariant::fromStdVariant(param_info.value)); } - userprefs.endGroup(); // standardParams } diff --git a/src/widgets.hpp b/src/widgets.hpp index 4c53801e6..8d2fbe41a 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -29,6 +29,7 @@ Q_DECLARE_METATYPE(IO::flags_t) Q_DECLARE_METATYPE(IO::endpoint) Q_DECLARE_METATYPE(RT::block_connection_t) Q_DECLARE_METATYPE(RT::State::state_t) +Q_DECLARE_METATYPE(std::string) class QSettings; /*! From 9c85af8bac01110b111c4e07ac9d233261960c16 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Wed, 31 Jul 2024 00:09:18 -0400 Subject: [PATCH 21/36] Added automatic update to panel parameters after loading of settings. Moved virtual class definitions for settings to implementation files. WIP --- src/widgets.cpp | 22 +++++++++++++++------- src/widgets.hpp | 4 ++-- 2 files changed, 17 insertions(+), 9 deletions(-) diff --git a/src/widgets.cpp b/src/widgets.cpp index 3f71686c0..9c90f7432 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -669,15 +669,17 @@ void Widgets::Plugin::loadParameterSettings(QSettings& userprefs) for (const auto& param_info : this->getComponentParametersInfo()) { id_str = QString::number(param_info.id); value = userprefs.value(id_str); - if(!value.isValid()){ - ERROR_MSG("Widgets::Plugin::loadParameterSettings : The loaded setting for " - "parameter {} is not valid! skipping...", param_info.name); + if (!value.isValid()) { + ERROR_MSG( + "Widgets::Plugin::loadParameterSettings : The loaded setting for " + "parameter {} is not valid! skipping...", + param_info.name); continue; } - // NOTE: Here we will assume that the type of the stored parameter matches the - // one stored inside the component. This may not be true in the future if the - // plugin developer decides to change the types of parameters. In this case, the - // QVariant will return 0 instead. + // NOTE: Here we will assume that the type of the stored parameter matches + // the one stored inside the component. This may not be true in the future + // if the plugin developer decides to change the types of parameters. In + // this case, the QVariant will return 0 instead. switch (param_info.vartype) { case Widgets::Variable::INT_PARAMETER: this->setComponentParameter( @@ -700,8 +702,12 @@ void Widgets::Plugin::loadParameterSettings(QSettings& userprefs) break; } } + // We should reflect the changes in the panel + this->getPanel()->refresh(); } +void Widgets::Plugin::loadCustomParameterSettings(QSettings& /*userprefs*/) {} + void Widgets::Plugin::saveParameterSettings(QSettings& userprefs) const { for (const auto& param_info : this->getComponentParametersInfo()) { @@ -709,3 +715,5 @@ void Widgets::Plugin::saveParameterSettings(QSettings& userprefs) const QVariant::fromStdVariant(param_info.value)); } } + +void Widgets::Plugin::saveCustomParameterSettings(QSettings& /*userprefs*/) const {} diff --git a/src/widgets.hpp b/src/widgets.hpp index 8d2fbe41a..30a5a94d9 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -667,9 +667,9 @@ class Plugin : public Event::Handler bool hasComponent() { return plugin_component != nullptr; } void loadParameterSettings(QSettings& userprefs); - virtual void loadCustomParameterSettings(QSettings& userprefs) {} + virtual void loadCustomParameterSettings(QSettings& userprefs); void saveParameterSettings(QSettings& userprefs) const ; - virtual void saveCustomParameterSettings(QSettings& userprefs) const {} + virtual void saveCustomParameterSettings(QSettings& userprefs) const; protected: Widgets::Component* getComponent(); From 913a02f9bbcdab908fd029562caf571e304a60f1 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Tue, 13 Aug 2024 23:49:42 -0400 Subject: [PATCH 22/36] added settings related functions to base widget classess and some documentation --- src/main_window.cpp | 238 ++++++++++++++++++++++++++++++++++---------- src/main_window.hpp | 10 ++ src/widgets.cpp | 13 ++- src/widgets.hpp | 42 +++++++- 4 files changed, 248 insertions(+), 55 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index 67d88d79a..0b1d64aef 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -30,7 +30,6 @@ #include #include "main_window.hpp" - #include #include "connector/connector.hpp" @@ -352,32 +351,142 @@ void MainWindow::loadWindow() show(); } -void MainWindow::loadSettings() +void MainWindow::savePeriodSettings(QSettings& userprefs) { - QSettings userprefs; - userprefs.beginGroup("Workspaces"); - auto* load_settings_dialog = new QInputDialog(this); - load_settings_dialog->setInputMode(QInputDialog::TextInput); - load_settings_dialog->setComboBoxEditable(false); - load_settings_dialog->setComboBoxItems(userprefs.childGroups()); - load_settings_dialog->setLabelText("Profile"); - load_settings_dialog->setOkButtonText("Load"); - load_settings_dialog->exec(); + Event::Object get_period_event(Event::Type::RT_GET_PERIOD_EVENT); + event_manager->postEvent(&get_period_event); + const auto period = + std::any_cast(get_period_event.getParam("period")); + userprefs.setValue("period", QString::number(period)); +} - if (load_settings_dialog->result() == QDialog::Rejected) { - userprefs.endGroup(); - return; - } - const QString profile = load_settings_dialog->textValue(); - mdiArea->closeAllSubWindows(); - userprefs.beginGroup(profile); +void MainWindow::loadPeriodSettings(QSettings& userprefs) +{ const auto period = userprefs.value("period", QVariant::fromValue(RT::OS::DEFAULT_PERIOD)) .value(); Event::Object event(Event::Type::RT_PERIOD_EVENT); event.setParam("period", std::any(period)); this->event_manager->postEvent(&event); +} + +void MainWindow::saveDAQSettings(QSettings& userprefs) +{ + userprefs.beginGroup("DAQs"); + Event::Object get_devices_event(Event::Type::DAQ_DEVICE_QUERY_EVENT); + this->event_manager->postEvent(&get_devices_event); + auto devices = std::any_cast>( + get_devices_event.getParam("devices")); + QString channel_name; + QString dev_name; + for (const auto& device : devices) { + dev_name = QString::fromStdString(device->getName()); + userprefs.beginGroup(dev_name); + channel_name = "ai_"; + for (size_t ai_channel = 0; + ai_channel < device->getChannelCount(DAQ::ChannelType::AI); + ++ai_channel) + { + userprefs.beginGroup(channel_name + QString::number(ai_channel)); + userprefs.setValue( + "active", device->getChannelActive(DAQ::ChannelType::AI, ai_channel)); + userprefs.setValue("downsample", + static_cast(device->getAnalogDownsample( + DAQ::ChannelType::AI, ai_channel))); + userprefs.setValue( + "gain", device->getAnalogGain(DAQ::ChannelType::AI, ai_channel)); + userprefs.setValue( + "offset", + device->getAnalogZeroOffset(DAQ::ChannelType::AI, ai_channel)); + userprefs.setValue("range", + static_cast(device->getAnalogRange( + DAQ::ChannelType::AI, ai_channel))); + userprefs.setValue("reference", + static_cast(device->getAnalogReference( + DAQ::ChannelType::AI, ai_channel))); + userprefs.setValue("units", + static_cast(device->getAnalogUnits( + DAQ::ChannelType::AI, ai_channel))); + userprefs.endGroup(); + } + channel_name = "ao_"; + for (size_t ao_channel = 0; + ao_channel < device->getChannelCount(DAQ::ChannelType::AO); + ++ao_channel) + { + userprefs.beginGroup(channel_name + QString::number(ao_channel)); + userprefs.setValue( + "active", device->getChannelActive(DAQ::ChannelType::AO, ao_channel)); + userprefs.setValue("downsample", + static_cast(device->getAnalogDownsample( + DAQ::ChannelType::AO, ao_channel))); + userprefs.setValue( + "gain", device->getAnalogGain(DAQ::ChannelType::AO, ao_channel)); + userprefs.setValue( + "offset", + device->getAnalogZeroOffset(DAQ::ChannelType::AO, ao_channel)); + userprefs.setValue("range", + static_cast(device->getAnalogRange( + DAQ::ChannelType::AO, ao_channel))); + userprefs.setValue("reference", + static_cast(device->getAnalogReference( + DAQ::ChannelType::AO, ao_channel))); + userprefs.setValue("units", + static_cast(device->getAnalogUnits( + DAQ::ChannelType::AO, ao_channel))); + userprefs.endGroup(); + } + channel_name = "di_"; + for (size_t di_channel = 0; + di_channel < device->getChannelCount(DAQ::ChannelType::DI); + ++di_channel) + { + userprefs.beginGroup(channel_name + QString::number(di_channel)); + userprefs.setValue( + "active", device->getChannelActive(DAQ::ChannelType::DI, di_channel)); + userprefs.endGroup(); + } + channel_name = "do_"; + for (size_t do_channel = 0; + do_channel < device->getChannelCount(DAQ::ChannelType::DO); + ++do_channel) + { + userprefs.beginGroup(channel_name + QString::number(do_channel)); + userprefs.setValue( + "active", device->getChannelActive(DAQ::ChannelType::DO, do_channel)); + userprefs.endGroup(); + } + userprefs.endGroup(); // Device name + } + userprefs.endGroup(); // DAQ +} + +void MainWindow::loadDAQSettings(QSettings& userprefs) {} + +void MainWindow::saveWidgetSettings(QSettings& userprefs) +{ + userprefs.beginGroup("Widgets"); + Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); + this->event_manager->postEvent(&loaded_plugins_query); + const auto plugin_list = std::any_cast>( + loaded_plugins_query.getParam("plugins")); + for (const auto& entry : plugin_list) { + userprefs.beginGroup(QString::number(entry->getID())); + userprefs.setValue("library", QString::fromStdString(entry->getLibrary())); + userprefs.beginGroup("standardParams"); + entry->saveParameterSettings(userprefs); + userprefs.endGroup(); // standardParams + userprefs.beginGroup("customParams"); + entry->saveCustomParameterSettings(userprefs); + userprefs.endGroup(); // customParams + userprefs.endGroup(); // widget count + } + userprefs.endGroup(); // Widgets +} + +void MainWindow::loadWidgetSettings(QSettings& userprefs) +{ userprefs.beginGroup("Widgets"); QString plugin_name; std::variant value; @@ -396,9 +505,57 @@ void MainWindow::loadSettings() userprefs.endGroup(); // customParams userprefs.endGroup(); // plugin_instance_id } + userprefs.endGroup(); +} + +void MainWindow::saveConnectionSettings(QSettings& userprefs) +{ + userprefs.beginGroup("Connections"); + userprefs.endGroup(); +} + +void MainWindow::loadConnectionSettings(QSettings& userprefs) +{ + Event::Object all_connections_event(Event::Type::IO_CONNECTION_QUERY_EVENT); + event_manager->postEvent(&all_connections_event); + auto connections = std::any_cast>( + all_connections_event.getParam("connections")); + std::unordered_map> block_connections; + for(const auto& conn : connections){ + block_connections[conn.src->getID()].push_back(conn); + } +} + +void MainWindow::loadSettings() +{ + QSettings userprefs; + userprefs.beginGroup("Workspaces"); + auto* load_settings_dialog = new QInputDialog(this); + load_settings_dialog->setInputMode(QInputDialog::TextInput); + load_settings_dialog->setComboBoxEditable(false); + load_settings_dialog->setComboBoxItems(userprefs.childGroups()); + load_settings_dialog->setLabelText("Profile"); + load_settings_dialog->setOkButtonText("Load"); + load_settings_dialog->exec(); + + if (load_settings_dialog->result() == QDialog::Rejected) { + userprefs.endGroup(); + return; + } + + const QString profile = load_settings_dialog->textValue(); + mdiArea->closeAllSubWindows(); + userprefs.beginGroup(profile); + + this->loadPeriodSettings(userprefs); + + this->loadDAQSettings(userprefs); + + this->loadWidgetSettings(userprefs); + + this->loadConnectionSettings(userprefs); userprefs.endGroup(); // profile - userprefs.endGroup(); // widgets userprefs.endGroup(); // workspaces } @@ -414,45 +571,25 @@ void MainWindow::saveSettings() save_settings_dialog->setOkButtonText("Save"); save_settings_dialog->exec(); + if (save_settings_dialog->result() == QDialog::Rejected) { + userprefs.endGroup(); + return; + } + const QString profile_name = save_settings_dialog->textValue(); if (userprefs.childGroups().contains(profile_name)) { userprefs.remove(profile_name); } + userprefs.beginGroup(profile_name); - // get period and save - Event::Object get_period_event(Event::Type::RT_GET_PERIOD_EVENT); - event_manager->postEvent(&get_period_event); - const auto period = - std::any_cast(get_period_event.getParam("period")); - userprefs.setValue("period", QString::number(period)); + this->savePeriodSettings(userprefs); - // Safe DAQ userprefs - userprefs.beginGroup("DAQs"); - userprefs.endGroup(); + this->saveDAQSettings(userprefs); - // Safe Widget userprefs - userprefs.beginGroup("Widgets"); - int widget_count = 0; - Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); - this->event_manager->postEvent(&loaded_plugins_query); - const auto plugin_list = std::any_cast>( - loaded_plugins_query.getParam("plugins")); - for (const auto& entry : plugin_list) { - userprefs.beginGroup(QString::number(widget_count++)); - userprefs.setValue("library", QString::fromStdString(entry->getLibrary())); - userprefs.beginGroup("standardParams"); - entry->saveParameterSettings(userprefs); - userprefs.endGroup(); // standardParams - userprefs.beginGroup("customParams"); - entry->saveCustomParameterSettings(userprefs); - userprefs.endGroup(); // customParams - userprefs.endGroup(); // widget count - } - userprefs.endGroup(); // Widgets + this->saveWidgetSettings(userprefs); - userprefs.beginGroup("Connections"); - userprefs.endGroup(); // Connections + this->saveConnectionSettings(userprefs); userprefs.endGroup(); // profile userprefs.endGroup(); // Workspaces @@ -495,7 +632,8 @@ void MainWindow::loadWidget(const QString& module_name, auto create_rtxi_panel_func = std::any_cast( event.getParam("createRTXIPanel")); - rtxi_plugin_pointer = std::any_cast(event.getParam("pluginPointer")); + rtxi_plugin_pointer = + std::any_cast(event.getParam("pluginPointer")); auto* rtxi_panel_pointer = create_rtxi_panel_func(this, this->event_manager); rtxi_plugin_pointer->attachPanel(rtxi_panel_pointer); // finally plugins can also receive events so make sure to register them diff --git a/src/main_window.hpp b/src/main_window.hpp index ffa0cf359..25c9cd63d 100644 --- a/src/main_window.hpp +++ b/src/main_window.hpp @@ -32,6 +32,8 @@ #include "event.hpp" +class QSettings; + namespace Widgets{ class Plugin; } // namespace Widgets @@ -165,6 +167,14 @@ private slots: private: void loadWidget(const QString& module_name); void loadWidget(const QString& module_name, Widgets::Plugin*& rtxi_plugin_pointer); + inline void savePeriodSettings(QSettings& userprefs); + inline void loadPeriodSettings(QSettings& userprefs); + inline void saveDAQSettings(QSettings& userprefs); + inline void loadDAQSettings(QSettings& userprefs); + inline void saveWidgetSettings(QSettings& userprefs); + inline void loadWidgetSettings(QSettings& userprefs); + inline void saveConnectionSettings(QSettings& userprefs); + inline void loadConnectionSettings(QSettings& userprefs); Event::Manager* event_manager; QMdiArea* mdiArea = nullptr; QList subWindows; diff --git a/src/widgets.cpp b/src/widgets.cpp index 9c90f7432..f2822aab2 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -567,6 +567,14 @@ Widgets::Plugin::getComponentParametersInfo() const : this->plugin_component->getParametersInfo(); } +size_t Widgets::Plugin::getID() const +{ + if(this->hasComponent()){ + return plugin_component->getID(); + } + return 0; +} + void Widgets::Plugin::attachComponent( std::unique_ptr component) { @@ -716,4 +724,7 @@ void Widgets::Plugin::saveParameterSettings(QSettings& userprefs) const } } -void Widgets::Plugin::saveCustomParameterSettings(QSettings& /*userprefs*/) const {} +void Widgets::Plugin::saveCustomParameterSettings( + QSettings& /*userprefs*/) const +{ +} diff --git a/src/widgets.hpp b/src/widgets.hpp index 30a5a94d9..090ceaa7d 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -276,7 +276,6 @@ class Component : public RT::Thread */ Widgets::Plugin* getHostPlugin() { return this->hostPlugin; } - private: std::vector parameters; Widgets::Plugin* hostPlugin; @@ -502,7 +501,7 @@ class Plugin : public Event::Handler * * \return ID of the widget assigned by the realtime system */ - size_t getID(); + size_t getID() const; /*! * Attaches a component to this plugin @@ -664,11 +663,46 @@ class Plugin : public Event::Handler * * \return True if there is an attached component, False otherwise. */ - bool hasComponent() { return plugin_component != nullptr; } + bool hasComponent() const { return plugin_component != nullptr; } + /*! + * Function called my the main window when loading settings to automatically + * retrieve parameter values in widget. + * + * \param userprefs A reference to QSettings object where the settings will be + * dumped + */ void loadParameterSettings(QSettings& userprefs); + + /*! + * Pass in a QSetting object for the plugin to load custom values loaded by the + * custom parameters. + * + * \param userprefs a standard QSettings object that the plugin can use to + * dump all of the settings as key/value pairs where the key + * is the name of the parameter and the value is the actual + * parameter value to store in the QSetting + */ virtual void loadCustomParameterSettings(QSettings& userprefs); - void saveParameterSettings(QSettings& userprefs) const ; + + /*! + * Function called my the main window when saving settings to automatically + * store parameter from widget. + * + * \param userprefs A reference to QSettings object where the settings will be + * dumped + */ + void saveParameterSettings(QSettings& userprefs) const; + + /*! + * Pass in a QSetting object for the plugin to save custom parameters + * + * + * \param userprefs a standard QSettings object that the plugin can use to + * dump all of the settings as key/value pairs where the key + * is the name of the parameter and the value is the actual + * parameter value to store in the QSetting + */ virtual void saveCustomParameterSettings(QSettings& userprefs) const; protected: From e3fe714b68e0d34fef3c62fba8492b678cce3710 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 17 Aug 2024 21:31:28 -0400 Subject: [PATCH 23/36] More changes. Settings now save some connection information. WIP --- src/event.hpp | 2 +- src/main_window.cpp | 115 +++++++++++++++++++++++++++++++++++--------- src/main_window.hpp | 2 - src/widgets.hpp | 13 +++-- 4 files changed, 104 insertions(+), 28 deletions(-) diff --git a/src/event.hpp b/src/event.hpp index fb6d18188..b5a569382 100644 --- a/src/event.hpp +++ b/src/event.hpp @@ -72,7 +72,7 @@ enum Type IO_LINK_REMOVE_EVENT, IO_BLOCK_QUERY_EVENT, IO_BLOCK_OUTPUTS_QUERY_EVENT, - IO_CONNECTION_QUERY_EVENT, + IO_CONNECTION_QUERY_EVENT, // TODO: Implement for connector IO_ALL_CONNECTIONS_QUERY_EVENT, PLUGIN_INSERT_EVENT, PLUGIN_REMOVE_EVENT, diff --git a/src/main_window.cpp b/src/main_window.cpp index 0b1d64aef..1eaa6fc81 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -19,6 +19,7 @@ */ #include +#include #include #include #include @@ -30,6 +31,7 @@ #include #include "main_window.hpp" + #include #include "connector/connector.hpp" @@ -38,11 +40,49 @@ #include "module_installer/rtxi_wizard.hpp" #include "oscilloscope/oscilloscope.hpp" #include "performance_measurement/performance_measurement.hpp" +#include "rt.hpp" #include "rtxiConfig.h" #include "system_control/system_control.hpp" #include "userprefs/userprefs.hpp" #include "widgets.hpp" +// This is defined here because top level function is the only other class +// in entire RTXI that needs to deal with connections, but I don't want to +// use block pointers directly here +// NOTE: In order to save this for serialization, we need to define stream +// operators so that Qt can serialize it for use inside the settings, and +// deserialize it back when loading settings. +struct plugin_connection +{ + quint64 src_id; + quint64 src_direction; + quint64 src_port; + quint64 dest_id; + quint64 dest_port; +}; + +QDataStream& operator<<(QDataStream& out, const plugin_connection& conn) +{ + out << conn.src_id; + out << conn.src_direction; + out << conn.src_port; + out << conn.dest_id; + out << conn.dest_port; + return out; +} + +QDataStream& operator>>(QDataStream& in, plugin_connection& conn) +{ + in >> conn.dest_port; + in >> conn.dest_id; + in >> conn.src_port; + in >> conn.src_direction; + in >> conn.src_id; + return in; +} + +Q_DECLARE_METATYPE(plugin_connection) + MainWindow::MainWindow(Event::Manager* ev_manager) : QMainWindow(nullptr, Qt::Window) , event_manager(ev_manager) @@ -80,6 +120,11 @@ MainWindow::MainWindow(Event::Manager* ev_manager) /* Initialize Help Menu */ createHelpActions(); createHelpMenu(); + + // Define a custom type to qt type system for settings management + qRegisterMetaType(); + qRegisterMetaTypeStreamOperators(); + } QAction* MainWindow::insertWidgetMenuSeparator() @@ -466,6 +511,7 @@ void MainWindow::loadDAQSettings(QSettings& userprefs) {} void MainWindow::saveWidgetSettings(QSettings& userprefs) { + ///////////////////// Save Widget parameters //////////////////////// userprefs.beginGroup("Widgets"); Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); this->event_manager->postEvent(&loaded_plugins_query); @@ -483,13 +529,33 @@ void MainWindow::saveWidgetSettings(QSettings& userprefs) userprefs.endGroup(); // widget count } userprefs.endGroup(); // Widgets + ///////////////////// Save connections ///////////////////////// + Event::Object all_connections_event( + Event::Type::IO_ALL_CONNECTIONS_QUERY_EVENT); + event_manager->postEvent(&all_connections_event); + auto connections = std::any_cast>( + all_connections_event.getParam("connections")); + plugin_connection id_connection {}; + userprefs.beginGroup("Connections"); + int connection_count = 0; + for (const auto& conn : connections) { + id_connection.src_id = conn.src->getID(); + id_connection.src_direction = conn.src_port_type; + id_connection.src_port = conn.src_port; + id_connection.dest_id = conn.dest->getID(); + id_connection.dest_port = conn.dest_port; + userprefs.setValue(QString::number(connection_count++), + QVariant::fromValue(id_connection)); + } + userprefs.endGroup(); // Connections } void MainWindow::loadWidgetSettings(QSettings& userprefs) { + ///////////////////// Load Widget parameters //////////////////////// + std::unordered_map blocks; userprefs.beginGroup("Widgets"); QString plugin_name; - std::variant value; Widgets::Plugin* plugin_ptr = nullptr; std::string event_status; for (const auto& plugin_instance_id : userprefs.childGroups()) { @@ -504,26 +570,35 @@ void MainWindow::loadWidgetSettings(QSettings& userprefs) plugin_ptr->loadCustomParameterSettings(userprefs); userprefs.endGroup(); // customParams userprefs.endGroup(); // plugin_instance_id + blocks[plugin_instance_id.toUInt()] = plugin_ptr->getBlock(); } - userprefs.endGroup(); -} - -void MainWindow::saveConnectionSettings(QSettings& userprefs) -{ + userprefs.endGroup(); // Widgets + ///////////////////// Load connections ///////////////////////// + RT::block_connection_t connection; + std::vector connection_events; + plugin_connection id_connection {}; userprefs.beginGroup("Connections"); - userprefs.endGroup(); -} - -void MainWindow::loadConnectionSettings(QSettings& userprefs) -{ - Event::Object all_connections_event(Event::Type::IO_CONNECTION_QUERY_EVENT); - event_manager->postEvent(&all_connections_event); - auto connections = std::any_cast>( - all_connections_event.getParam("connections")); - std::unordered_map> block_connections; - for(const auto& conn : connections){ - block_connections[conn.src->getID()].push_back(conn); + for (const auto& conn_count : userprefs.childGroups()) { + id_connection = userprefs.value(conn_count).value(); + if (blocks.find(id_connection.src_id) == blocks.end() + || blocks.find(id_connection.dest_id) == blocks.end()) + { + ERROR_MSG( + "MainWindow::loadWidgetSettings : invalid connection found. " + "Skipping"); + continue; + } + connection.src = blocks[id_connection.src_id]; + connection.src_port_type = + static_cast(id_connection.src_direction); + connection.src_port = id_connection.src_port; + connection.dest = blocks[id_connection.dest_id]; + connection.dest_port = id_connection.dest_port; + connection_events.emplace_back(Event::Type::IO_LINK_INSERT_EVENT); + connection_events.back().setParam("connection", std::any(connection)); } + userprefs.endGroup(); // Connections + event_manager->postEvent(connection_events); } void MainWindow::loadSettings() @@ -553,8 +628,6 @@ void MainWindow::loadSettings() this->loadWidgetSettings(userprefs); - this->loadConnectionSettings(userprefs); - userprefs.endGroup(); // profile userprefs.endGroup(); // workspaces } @@ -589,8 +662,6 @@ void MainWindow::saveSettings() this->saveWidgetSettings(userprefs); - this->saveConnectionSettings(userprefs); - userprefs.endGroup(); // profile userprefs.endGroup(); // Workspaces } diff --git a/src/main_window.hpp b/src/main_window.hpp index 25c9cd63d..3b83b64f0 100644 --- a/src/main_window.hpp +++ b/src/main_window.hpp @@ -173,8 +173,6 @@ private slots: inline void loadDAQSettings(QSettings& userprefs); inline void saveWidgetSettings(QSettings& userprefs); inline void loadWidgetSettings(QSettings& userprefs); - inline void saveConnectionSettings(QSettings& userprefs); - inline void loadConnectionSettings(QSettings& userprefs); Event::Manager* event_manager; QMdiArea* mdiArea = nullptr; QList subWindows; diff --git a/src/widgets.hpp b/src/widgets.hpp index 090ceaa7d..debec850f 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -675,8 +675,8 @@ class Plugin : public Event::Handler void loadParameterSettings(QSettings& userprefs); /*! - * Pass in a QSetting object for the plugin to load custom values loaded by the - * custom parameters. + * Pass in a QSetting object for the plugin to load custom values loaded by + * the custom parameters. * * \param userprefs a standard QSettings object that the plugin can use to * dump all of the settings as key/value pairs where the key @@ -695,7 +695,7 @@ class Plugin : public Event::Handler void saveParameterSettings(QSettings& userprefs) const; /*! - * Pass in a QSetting object for the plugin to save custom parameters + * Pass in a QSetting object for the plugin to save custom parameters * * * \param userprefs a standard QSettings object that the plugin can use to @@ -705,6 +705,13 @@ class Plugin : public Event::Handler */ virtual void saveCustomParameterSettings(QSettings& userprefs) const; + /*! + * get a pointer to the internal block of the plugin + * + * \return IO::Block pointer to the internal structure + */ + IO::Block* getBlock() { return plugin_component.get(); } + protected: Widgets::Component* getComponent(); Event::Manager* getEventManager(); From 517f774c92ba085c579e2e90fbe7712d6eac5785 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sun, 25 Aug 2024 19:19:12 -0400 Subject: [PATCH 24/36] Fixed bug where loading connection values from settings wasnt working --- src/main_window.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index 1eaa6fc81..31de593b6 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -578,7 +578,7 @@ void MainWindow::loadWidgetSettings(QSettings& userprefs) std::vector connection_events; plugin_connection id_connection {}; userprefs.beginGroup("Connections"); - for (const auto& conn_count : userprefs.childGroups()) { + for (const auto& conn_count : userprefs.childKeys()) { id_connection = userprefs.value(conn_count).value(); if (blocks.find(id_connection.src_id) == blocks.end() || blocks.find(id_connection.dest_id) == blocks.end()) From 35d59e1bd930cc0a00b3cee3fcd8c29f94144292 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 7 Sep 2024 21:37:36 -0400 Subject: [PATCH 25/36] added documentation for some functions --- src/widgets.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/widgets.hpp b/src/widgets.hpp index 986106cf5..a4a4e511a 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -648,6 +648,11 @@ class Plugin : public Event::Handler */ void setComponentState(RT::State::state_t state); + /*! + * Obtain the state of the components attached to the plugin + * + * \return An RT::State::state_t value representing the current state of the component + */ RT::State::state_t getComponentState(); /*! From 3ab53eb38d9f01f67919e6f1c26034d6e673e184 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sun, 8 Sep 2024 10:58:57 -0400 Subject: [PATCH 26/36] Fixed documentation generation issues for docs cmake preset --- docs/Doxyfile.in | 2 +- docs/conf.py.in | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/Doxyfile.in b/docs/Doxyfile.in index e940458f2..d1314280a 100644 --- a/docs/Doxyfile.in +++ b/docs/Doxyfile.in @@ -51,7 +51,7 @@ PROJECT_BRIEF = "The Real-Time eXperiment Interface Reference Manual" # pixels and the maximum width should not exceed 200 pixels. Doxygen will copy # the logo to the output directory. -PROJECT_LOGO = "res/icons/RTXI-icon.svg" +PROJECT_LOGO = "@PROJECT_SOURCE_DIR@/res/icons/RTXI-icon.svg" # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path # into which the generated documentation will be written. If a relative path is diff --git a/docs/conf.py.in b/docs/conf.py.in index b81e3d92a..f7c8616c0 100644 --- a/docs/conf.py.in +++ b/docs/conf.py.in @@ -1,6 +1,7 @@ DOXYFILE = 'Doxyfile' LINKS_NAVBAR1 = [ - (None, 'pages', [(None, 'about')]), + (None, 'pages', []), (None, 'namespaces', []), ] + From 1129c2f8986463df2f7cc33561df3b020d8de664 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 13 Sep 2024 01:03:32 -0400 Subject: [PATCH 27/36] Modified source to do as much forward declarations as possible to speed up compilation --- plugins/connector/connector.cpp | 11 +++++++++- plugins/connector/connector.hpp | 6 ++++-- plugins/data_recorder/data_recorder.cpp | 15 ++++++++++---- plugins/data_recorder/data_recorder.hpp | 20 +++++++++++-------- plugins/module_installer/rtxi_wizard.cpp | 8 ++++++++ plugins/module_installer/rtxi_wizard.hpp | 9 +++++---- plugins/oscilloscope/oscilloscope.cpp | 6 ++++++ plugins/oscilloscope/oscilloscope.hpp | 15 +++++++++++--- .../performance_measurement.cpp | 8 ++++++++ .../performance_measurement.hpp | 8 +++++--- plugins/system_control/system_control.cpp | 9 +++++++++ plugins/system_control/system_control.hpp | 8 ++++++-- plugins/userprefs/userprefs.cpp | 6 ++++++ src/event.cpp | 1 + src/logger.hpp | 5 ++++- src/main_window.cpp | 5 ++++- src/main_window.hpp | 15 +++++++------- src/rt.hpp | 8 ++++++-- src/widgets.cpp | 12 ++++++++--- src/widgets.hpp | 18 +++++++++-------- src/workspace.cpp | 14 +++++++------ src/workspace.hpp | 17 ++++++++++++---- test/system_tests.cpp | 1 + 23 files changed, 165 insertions(+), 60 deletions(-) diff --git a/plugins/connector/connector.cpp b/plugins/connector/connector.cpp index f23e4950d..a85ec4394 100644 --- a/plugins/connector/connector.cpp +++ b/plugins/connector/connector.cpp @@ -18,6 +18,14 @@ */ +#include +#include +#include +#include +#include +#include +#include + #include "connector.hpp" Connector::Panel::Panel(QMainWindow* mw, Event::Manager* ev_manager) @@ -452,7 +460,8 @@ void Connector::Panel::updateConnectionButton() for (int i = 0; i < connectionBox->count(); i++) { temp_item = connectionBox->item(i); if (temp_item->data(Qt::UserRole).value() - == connection) { + == connection) + { connectionButton->setDown(true); connectionButton->setChecked(true); return; diff --git a/plugins/connector/connector.hpp b/plugins/connector/connector.hpp index 88cdad242..bde1342f0 100644 --- a/plugins/connector/connector.hpp +++ b/plugins/connector/connector.hpp @@ -21,14 +21,16 @@ #ifndef CONNECTOR_H #define CONNECTOR_H -#include -#include #include #include "event.hpp" #include "io.hpp" #include "widgets.hpp" +class QComboBox; +class QListWidget; +class QListWidgetItem; + namespace Connector { constexpr std::string_view MODULE_NAME = "Connector"; diff --git a/plugins/data_recorder/data_recorder.cpp b/plugins/data_recorder/data_recorder.cpp index d9e6a30ec..a73eb1927 100644 --- a/plugins/data_recorder/data_recorder.cpp +++ b/plugins/data_recorder/data_recorder.cpp @@ -17,25 +17,32 @@ */ +#include #include +#include #include #include +#include #include -#include -#include +#include +#include +#include +#include +#include #include #include #include "data_recorder.hpp" #include -#include #include "debug.hpp" +#include "fifo.hpp" +#include "rtos.hpp" DataRecorder::Panel::Panel(QMainWindow* mwindow, Event::Manager* ev_manager) : Widgets::Panel( - std::string(DataRecorder::MODULE_NAME), mwindow, ev_manager) + std::string(DataRecorder::MODULE_NAME), mwindow, ev_manager) , buttonGroup(new QGroupBox) , blockList(new QComboBox) , channelList(new QComboBox) diff --git a/plugins/data_recorder/data_recorder.hpp b/plugins/data_recorder/data_recorder.hpp index 95989f433..d9e2364d1 100644 --- a/plugins/data_recorder/data_recorder.hpp +++ b/plugins/data_recorder/data_recorder.hpp @@ -20,20 +20,24 @@ #ifndef DATA_RECORDER_H #define DATA_RECORDER_H -#include -#include -#include -#include #include -#include #include #include -#include -#include "event.hpp" #include "io.hpp" #include "widgets.hpp" +#include "fifo.hpp" + +class QComboBox; +class QListWidget; +class QMutex; +class QSpinBox; + +namespace Event +{ +class Manager; +} // namespace Event namespace DataRecorder { @@ -65,7 +69,7 @@ typedef struct record_channel { std::string name; IO::endpoint endpoint; - RT::OS::Fifo* data_source=nullptr; + RT::OS::Fifo* data_source = nullptr; bool operator==(const record_channel& rhs) const { return (this->endpoint == rhs.endpoint) diff --git a/plugins/module_installer/rtxi_wizard.cpp b/plugins/module_installer/rtxi_wizard.cpp index 23862412e..f3392a3ab 100644 --- a/plugins/module_installer/rtxi_wizard.cpp +++ b/plugins/module_installer/rtxi_wizard.cpp @@ -19,10 +19,18 @@ #include #include #include +#include +#include #include #include #include +#include +#include #include +#include +#include +#include +#include #include #include "rtxi_wizard.hpp" diff --git a/plugins/module_installer/rtxi_wizard.hpp b/plugins/module_installer/rtxi_wizard.hpp index f6fd9c167..541502516 100644 --- a/plugins/module_installer/rtxi_wizard.hpp +++ b/plugins/module_installer/rtxi_wizard.hpp @@ -20,15 +20,16 @@ #define RTXI_WIZARD_H #include -#include #include -#include -#include -#include #include #include "widgets.hpp" +class QListWidget; +class QProgressDialog; +class QTextEdit; +class QNetworkReply; + namespace RTXIWizard { diff --git a/plugins/oscilloscope/oscilloscope.cpp b/plugins/oscilloscope/oscilloscope.cpp index 35881333e..fb9005a44 100644 --- a/plugins/oscilloscope/oscilloscope.cpp +++ b/plugins/oscilloscope/oscilloscope.cpp @@ -25,6 +25,11 @@ */ #include +#include +#include +#include +#include +#include #include #include #include @@ -35,6 +40,7 @@ #include "debug.hpp" #include "rt.hpp" +#include "rtos.hpp" #include "scope.hpp" void Oscilloscope::Plugin::receiveEvent(Event::Object* event) diff --git a/plugins/oscilloscope/oscilloscope.hpp b/plugins/oscilloscope/oscilloscope.hpp index 1fd661360..c12c36bbc 100644 --- a/plugins/oscilloscope/oscilloscope.hpp +++ b/plugins/oscilloscope/oscilloscope.hpp @@ -29,13 +29,22 @@ #include -#include "event.hpp" -#include "fifo.hpp" #include "io.hpp" -#include "rt.hpp" #include "scope.hpp" #include "widgets.hpp" +namespace Event{ +class Manager; +class Object; +} // namespace Event + +namespace RT::OS{ +class Fifo; +} // namespace RT::OS + +class QVBoxLayout; +class QButtonGroup; + namespace Oscilloscope { diff --git a/plugins/performance_measurement/performance_measurement.cpp b/plugins/performance_measurement/performance_measurement.cpp index ef9d19afe..f81efe014 100644 --- a/plugins/performance_measurement/performance_measurement.cpp +++ b/plugins/performance_measurement/performance_measurement.cpp @@ -17,11 +17,19 @@ */ +#include +#include +#include +#include +#include + #include "performance_measurement.hpp" #include "debug.hpp" #include "event.hpp" +#include "fifo.hpp" #include "rt.hpp" +#include "rtos.hpp" #include "widgets.hpp" PerformanceMeasurement::Panel::Panel(const std::string& mod_name, diff --git a/plugins/performance_measurement/performance_measurement.hpp b/plugins/performance_measurement/performance_measurement.hpp index 5c152467f..5d74626bf 100644 --- a/plugins/performance_measurement/performance_measurement.hpp +++ b/plugins/performance_measurement/performance_measurement.hpp @@ -21,12 +21,14 @@ #ifndef PERFORMANCE_MEASUREMENT_H #define PERFORMANCE_MEASUREMENT_H -#include - #include "math/runningstat.h" #include "widgets.hpp" -#include "rt.hpp" +namespace RT::OS{ +class Fifo; +} // namespace RT::OS + +class QLineEdit; namespace PerformanceMeasurement { diff --git a/plugins/system_control/system_control.cpp b/plugins/system_control/system_control.cpp index 3f9bd9115..408a2bae7 100644 --- a/plugins/system_control/system_control.cpp +++ b/plugins/system_control/system_control.cpp @@ -17,6 +17,13 @@ */ +#include +#include +#include +#include +#include +#include +#include #include #include @@ -24,6 +31,8 @@ #include "daq.hpp" #include "rt.hpp" +#include "rtos.hpp" +#include "event.hpp" SystemControl::Panel::Panel(QMainWindow* mw, Event::Manager* ev_manager) : Widgets::Panel(std::string(SystemControl::MODULE_NAME), mw, ev_manager) diff --git a/plugins/system_control/system_control.hpp b/plugins/system_control/system_control.hpp index 11795f9b8..370e009e1 100644 --- a/plugins/system_control/system_control.hpp +++ b/plugins/system_control/system_control.hpp @@ -20,10 +20,8 @@ #ifndef SYSTEM_CONTROL_H #define SYSTEM_CONTROL_H -#include #include "daq.hpp" -#include "event.hpp" #include "widgets.hpp" Q_DECLARE_METATYPE(DAQ::ChannelType::type_t) @@ -32,6 +30,12 @@ Q_DECLARE_METATYPE(DAQ::direction_t) Q_DECLARE_METATYPE(DAQ::Reference::reference_t) Q_DECLARE_METATYPE(DAQ::analog_range_t) +class QComboBox; +namespace Event{ +class Manager; +class Object; +} // namespace Event + namespace SystemControl { diff --git a/plugins/userprefs/userprefs.cpp b/plugins/userprefs/userprefs.cpp index 52c33f39f..cd4346ee8 100644 --- a/plugins/userprefs/userprefs.cpp +++ b/plugins/userprefs/userprefs.cpp @@ -24,6 +24,12 @@ */ #include +#include +#include +#include +#include +#include +#include #include "userprefs.hpp" diff --git a/src/event.cpp b/src/event.cpp index 776913388..f41f5e5ad 100644 --- a/src/event.cpp +++ b/src/event.cpp @@ -24,6 +24,7 @@ #include "event.hpp" #include "logger.hpp" +#include "rtos.hpp" std::string Event::type_to_string(Event::Type event_type) { diff --git a/src/logger.hpp b/src/logger.hpp index b50a5d1f1..adbf3123f 100644 --- a/src/logger.hpp +++ b/src/logger.hpp @@ -5,9 +5,12 @@ #include #include -#include "event.hpp" #include "rt.hpp" +namespace Event{ +class Object; +} // namespace Event + /*! * Class responsible for logging all events and telemitry */ diff --git a/src/main_window.cpp b/src/main_window.cpp index 31de593b6..7652a3d57 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -23,6 +23,9 @@ #include #include #include +#include +#include +#include #include #include #include @@ -41,6 +44,7 @@ #include "oscilloscope/oscilloscope.hpp" #include "performance_measurement/performance_measurement.hpp" #include "rt.hpp" +#include "rtos.hpp" #include "rtxiConfig.h" #include "system_control/system_control.hpp" #include "userprefs/userprefs.hpp" @@ -124,7 +128,6 @@ MainWindow::MainWindow(Event::Manager* ev_manager) // Define a custom type to qt type system for settings management qRegisterMetaType(); qRegisterMetaTypeStreamOperators(); - } QAction* MainWindow::insertWidgetMenuSeparator() diff --git a/src/main_window.hpp b/src/main_window.hpp index 3b83b64f0..d28a439c8 100644 --- a/src/main_window.hpp +++ b/src/main_window.hpp @@ -21,18 +21,17 @@ #ifndef MAIN_WINDOW_H #define MAIN_WINDOW_H -#include -#include -#include -#include -#include -#include -#include #include - +#include #include "event.hpp" class QSettings; +class QAction; +class QMdiArea; +class QMdiSubWindow; +class QMenu; +class QTextEdit; +class QTextItem; namespace Widgets{ class Plugin; diff --git a/src/rt.hpp b/src/rt.hpp index b288a2022..d3fe3f0e7 100644 --- a/src/rt.hpp +++ b/src/rt.hpp @@ -25,9 +25,13 @@ #include #include "event.hpp" -#include "fifo.hpp" #include "io.hpp" -#include "rtos.hpp" + +namespace RT::OS +{ +class Task; +class Fifo; +} // namespace RT::OS // forward declaration namespace Widgets diff --git a/src/widgets.cpp b/src/widgets.cpp index f2822aab2..d3272942b 100644 --- a/src/widgets.cpp +++ b/src/widgets.cpp @@ -2,11 +2,18 @@ #include #include #include +#include #include +#include +#include #include +#include +#include #include #include #include +#include +#include #include #include #include @@ -14,7 +21,6 @@ #include "widgets.hpp" #include -#include #include "debug.hpp" #include "event.hpp" @@ -569,8 +575,8 @@ Widgets::Plugin::getComponentParametersInfo() const size_t Widgets::Plugin::getID() const { - if(this->hasComponent()){ - return plugin_component->getID(); + if (this->hasComponent()) { + return plugin_component->getID(); } return 0; } diff --git a/src/widgets.hpp b/src/widgets.hpp index a4a4e511a..9e5e8e4f3 100644 --- a/src/widgets.hpp +++ b/src/widgets.hpp @@ -1,14 +1,7 @@ #ifndef WIDGET_HPP #define WIDGET_HPP -#include -#include -#include #include -#include -#include -#include -#include #include #include #include @@ -21,6 +14,14 @@ #include "io.hpp" #include "rt.hpp" +class QGridLayout; +class QGroupBox; +class QLabel; +class QMainWindow; +class QMdiSubWindow; +class QPushButton; +class QValidator; + // These metatype declarations are needed by qt to store // the types in QVariant, which is very convenient and reduces // unnecessary repetiotion in panel construction @@ -651,7 +652,8 @@ class Plugin : public Event::Handler /*! * Obtain the state of the components attached to the plugin * - * \return An RT::State::state_t value representing the current state of the component + * \return An RT::State::state_t value representing the current state of the + * component */ RT::State::state_t getComponentState(); diff --git a/src/workspace.cpp b/src/workspace.cpp index b0a95761d..a36e00e4c 100644 --- a/src/workspace.cpp +++ b/src/workspace.cpp @@ -16,8 +16,11 @@ #include "workspace.hpp" +#include + #include "connector/connector.hpp" #include "data_recorder/data_recorder.hpp" +#include "dlplugin.hpp" #include "module_installer/rtxi_wizard.hpp" #include "oscilloscope/oscilloscope.hpp" #include "performance_measurement/performance_measurement.hpp" @@ -57,10 +60,10 @@ Workspace::Manager::Manager(Event::Manager* ev_manager) const QDir bin_dir = QCoreApplication::applicationDirPath(); const std::string nidaq_driver_name = "librtxinidaqdriver.so"; if (bin_dir.exists(QString::fromStdString(nidaq_driver_name))) { - try{ + try { this->registerDriver(bin_dir.path().toStdString() + std::string("/") + nidaq_driver_name); - } catch (std::runtime_error& exception){ + } catch (std::runtime_error& exception) { ERROR_MSG("Unable to load NIDAQ rtxi driver"); } } @@ -69,7 +72,7 @@ Workspace::Manager::Manager(Event::Manager* ev_manager) try { this->registerDriver(bin_dir.path().toStdString() + std::string("/") + gsc_driver_name); - } catch (std::runtime_error& excepttion){ + } catch (std::runtime_error& excepttion) { ERROR_MSG("Unable to load GSC aio168 rtxi driver"); } } @@ -145,12 +148,11 @@ std::vector Workspace::Manager::getAllDevices() return devices; } - std::vector Workspace::Manager::getLoadedPlugins() { std::vector result; - for(const auto& entry : this->rtxi_widgets_registry){ - for(const auto& plugin : entry.second){ + for (const auto& entry : this->rtxi_widgets_registry) { + for (const auto& plugin : entry.second) { result.push_back(plugin.get()); } } diff --git a/src/workspace.hpp b/src/workspace.hpp index 145b3ede2..20fe5894a 100644 --- a/src/workspace.hpp +++ b/src/workspace.hpp @@ -16,13 +16,22 @@ #define WORKSPACE_H #include -#include -#include "daq.hpp" -#include "dlplugin.hpp" -#include "event.hpp" #include "widgets.hpp" +namespace Event{ +class Object; +} // namespace Event + +namespace DLL{ +class Loader; +} // namespace DLL + +namespace DAQ{ +class Device; +class Driver; +} // namespace DAQ + /*! * Objects contained within this namespace are responsible for providing * Manager objects. diff --git a/test/system_tests.cpp b/test/system_tests.cpp index b88c0865f..4c20e4b49 100644 --- a/test/system_tests.cpp +++ b/test/system_tests.cpp @@ -24,6 +24,7 @@ #include "system_tests.hpp" #include +#include "rtos.hpp" TEST_F(RTConnectorTest, connections) { From a19d82682860c4ef7c840c5f8232e7c507bb8d9e Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Fri, 13 Sep 2024 23:34:13 -0400 Subject: [PATCH 28/36] Forward declarations applied to scope objects in oscilloscope plugin --- plugins/oscilloscope/scope.cpp | 7 ++++++- plugins/oscilloscope/scope.hpp | 19 ++++++------------- 2 files changed, 12 insertions(+), 14 deletions(-) diff --git a/plugins/oscilloscope/scope.cpp b/plugins/oscilloscope/scope.cpp index 72f4e96c4..0e43c4886 100644 --- a/plugins/oscilloscope/scope.cpp +++ b/plugins/oscilloscope/scope.cpp @@ -25,9 +25,14 @@ #include #include +#include +#include +#include +#include +#include #include +#include #include -#include Oscilloscope::LegendItem::LegendItem() { diff --git a/plugins/oscilloscope/scope.hpp b/plugins/oscilloscope/scope.hpp index 6d9e4b254..f7cdd3894 100644 --- a/plugins/oscilloscope/scope.hpp +++ b/plugins/oscilloscope/scope.hpp @@ -34,24 +34,17 @@ #include #include -#include -#include -#include -#include -#include #include -#include -#include -#include -#include #include -#include -#include -#include - +#include #include "fifo.hpp" #include "io.hpp" +class QwtPlotCurve; +class QwtPlotDirectPainter; +class QwtPlotGrid; +class QwtPlotMarker; + namespace Oscilloscope { From 31367cb9e965f7bce815c54712b3d4814d4cb4f8 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 23 Sep 2024 15:16:30 -0400 Subject: [PATCH 29/36] Updated settings to ignore storing connections to oscilloscope probes and recorders --- src/main_window.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main_window.cpp b/src/main_window.cpp index 7652a3d57..c77f69d11 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -542,6 +542,14 @@ void MainWindow::saveWidgetSettings(QSettings& userprefs) userprefs.beginGroup("Connections"); int connection_count = 0; for (const auto& conn : connections) { + // NOTE: We don't handle connections that are managed by plugins themselves. + // Namely connections related to probes from oscilloscope and recorders from + // the recorder plugin + if (conn.dest->getName().find("Probe") != std::string::npos + || conn.dest->getName().find("Recording") != std::string::npos) + { + continue; + } id_connection.src_id = conn.src->getID(); id_connection.src_direction = conn.src_port_type; id_connection.src_port = conn.src_port; From 629bc87dffde2b0f6c5a8619eedeae4862e3c59d Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 7 Oct 2024 01:23:04 -0400 Subject: [PATCH 30/36] Finalizing settings feature --- src/main_window.cpp | 230 +++++++++++++++++++++++++++++++++++--------- src/main_window.hpp | 23 ++++- 2 files changed, 202 insertions(+), 51 deletions(-) diff --git a/src/main_window.cpp b/src/main_window.cpp index c77f69d11..c6cf2087c 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -31,13 +31,16 @@ #include #include #include +#include #include +#include #include "main_window.hpp" #include #include "connector/connector.hpp" +#include "daq.hpp" #include "data_recorder/data_recorder.hpp" #include "event.hpp" #include "module_installer/rtxi_wizard.hpp" @@ -426,17 +429,17 @@ void MainWindow::saveDAQSettings(QSettings& userprefs) this->event_manager->postEvent(&get_devices_event); auto devices = std::any_cast>( get_devices_event.getParam("devices")); - QString channel_name; QString dev_name; for (const auto& device : devices) { dev_name = QString::fromStdString(device->getName()); - userprefs.beginGroup(dev_name); - channel_name = "ai_"; + userprefs.beginGroup(QString::number(device->getID())); + userprefs.setValue("name", QString::fromStdString(device->getName())); + userprefs.beginGroup("AI"); for (size_t ai_channel = 0; ai_channel < device->getChannelCount(DAQ::ChannelType::AI); ++ai_channel) { - userprefs.beginGroup(channel_name + QString::number(ai_channel)); + userprefs.beginGroup(QString::number(ai_channel)); userprefs.setValue( "active", device->getChannelActive(DAQ::ChannelType::AI, ai_channel)); userprefs.setValue("downsample", @@ -456,14 +459,15 @@ void MainWindow::saveDAQSettings(QSettings& userprefs) userprefs.setValue("units", static_cast(device->getAnalogUnits( DAQ::ChannelType::AI, ai_channel))); - userprefs.endGroup(); + userprefs.endGroup(); // channel } - channel_name = "ao_"; + userprefs.endGroup(); // Analog Input + userprefs.beginGroup("AO"); for (size_t ao_channel = 0; ao_channel < device->getChannelCount(DAQ::ChannelType::AO); ++ao_channel) { - userprefs.beginGroup(channel_name + QString::number(ao_channel)); + userprefs.beginGroup(QString::number(ao_channel)); userprefs.setValue( "active", device->getChannelActive(DAQ::ChannelType::AO, ao_channel)); userprefs.setValue("downsample", @@ -485,36 +489,160 @@ void MainWindow::saveDAQSettings(QSettings& userprefs) DAQ::ChannelType::AO, ao_channel))); userprefs.endGroup(); } - channel_name = "di_"; + userprefs.endGroup(); // Analog Output + userprefs.beginGroup("DI"); for (size_t di_channel = 0; di_channel < device->getChannelCount(DAQ::ChannelType::DI); ++di_channel) { - userprefs.beginGroup(channel_name + QString::number(di_channel)); + userprefs.beginGroup(QString::number(di_channel)); userprefs.setValue( "active", device->getChannelActive(DAQ::ChannelType::DI, di_channel)); userprefs.endGroup(); } - channel_name = "do_"; + userprefs.endGroup(); // Digitial Input + userprefs.beginGroup("DO"); for (size_t do_channel = 0; do_channel < device->getChannelCount(DAQ::ChannelType::DO); ++do_channel) { - userprefs.beginGroup(channel_name + QString::number(do_channel)); + userprefs.beginGroup(QString::number(do_channel)); userprefs.setValue( "active", device->getChannelActive(DAQ::ChannelType::DO, do_channel)); userprefs.endGroup(); } - userprefs.endGroup(); // Device name + userprefs.endGroup(); // Digital Output + userprefs.endGroup(); // Device ID } userprefs.endGroup(); // DAQ } -void MainWindow::loadDAQSettings(QSettings& userprefs) {} +void MainWindow::loadDAQSettings( + QSettings& userprefs, std::unordered_map block_cache) +{ + userprefs.beginGroup("DAQs"); + Event::Object get_devices_event(Event::Type::DAQ_DEVICE_QUERY_EVENT); + this->event_manager->postEvent(&get_devices_event); + auto devices = std::any_cast>( + get_devices_event.getParam("devices")); + QString device_name; + QString channel_name; + DAQ::Device* tmp_device = nullptr; + DAQ::index_t current_channel_id = 0; + for (const auto& device_id : userprefs.childGroups()) { + userprefs.beginGroup(device_id); + device_name = userprefs.value("name").value(); + // NOTE: We need to make sure that the settings we are about to load are + // not reloaded for other devices. Therefore we check whether the name + // exists in the loaded devices registry and whether we already used + // the block in a previous iteration (could be the case when using multiple + // devices of the same type) + auto iter = + std::find_if(devices.begin(), + devices.end(), + [device_name, device_id, block_cache](IO::Block* block) + { + return (block->getName() == device_name.toStdString()) + && (std::find_if(block_cache.begin(), + block_cache.end(), + [block](const auto& entry) + { return entry.second == block; }) + != block_cache.end()); + }); + if (iter == devices.end()) { + ERROR_MSG("Unable to find DAQ device {} from the list of loaded devices.", + device_name.toStdString()); + userprefs.endGroup(); // device + continue; + } + tmp_device = *iter; + userprefs.beginGroup("AI"); + for (const auto& channel_id : userprefs.childGroups()) { + current_channel_id = channel_id.toUInt(); + userprefs.beginGroup(channel_id); + tmp_device->setChannelActive(DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("active").value()); + tmp_device->setAnalogDownsample( + DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("downsample").value()); + tmp_device->setAnalogGain(DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("gain").value()); + tmp_device->setAnalogZeroOffset( + DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("offset").value()); + tmp_device->setAnalogRange(DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("range").value()); + tmp_device->setAnalogReference( + DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("reference").value()); + tmp_device->setAnalogUnits(DAQ::ChannelType::AI, + current_channel_id, + userprefs.value("units").value()); + userprefs.endGroup(); // channel + } + userprefs.endGroup(); // Analog Input + userprefs.beginGroup("AO"); + + for (const auto& channel_id : userprefs.childGroups()) { + current_channel_id = channel_id.toUInt(); + userprefs.beginGroup(channel_id); + tmp_device->setChannelActive(DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("active").value()); + tmp_device->setAnalogDownsample( + DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("downsample").value()); + tmp_device->setAnalogGain(DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("gain").value()); + tmp_device->setAnalogZeroOffset( + DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("offset").value()); + tmp_device->setAnalogRange(DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("range").value()); + tmp_device->setAnalogReference( + DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("reference").value()); + tmp_device->setAnalogUnits(DAQ::ChannelType::AO, + current_channel_id, + userprefs.value("units").value()); + userprefs.endGroup(); // channel + } + userprefs.endGroup(); // Analog Output + userprefs.beginGroup("DI"); + for (const auto& channel_id : userprefs.childGroups()) { + current_channel_id = channel_id.toUInt(); + userprefs.beginGroup(channel_id); + tmp_device->setActive(userprefs.value("active").value()); + userprefs.endGroup(); + } + userprefs.endGroup(); // Digital Input + userprefs.beginGroup("DO"); + for (const auto& channel_id : userprefs.childGroups()) { + current_channel_id = channel_id.toUInt(); + userprefs.beginGroup(channel_name); + tmp_device->setActive(userprefs.value("active").value()); + userprefs.endGroup(); + } + userprefs.endGroup(); // Digital Output + userprefs.endGroup(); // Device name + block_cache[device_id.toUInt()] = tmp_device; + } + userprefs.endGroup(); // DAQ +} void MainWindow::saveWidgetSettings(QSettings& userprefs) { - ///////////////////// Save Widget parameters //////////////////////// userprefs.beginGroup("Widgets"); Event::Object loaded_plugins_query(Event::Type::PLUGIN_LIST_QUERY_EVENT); this->event_manager->postEvent(&loaded_plugins_query); @@ -532,7 +660,34 @@ void MainWindow::saveWidgetSettings(QSettings& userprefs) userprefs.endGroup(); // widget count } userprefs.endGroup(); // Widgets - ///////////////////// Save connections ///////////////////////// +} + +void MainWindow::loadWidgetSettings( + QSettings& userprefs, std::unordered_map block_cache) +{ + userprefs.beginGroup("Widgets"); + QString plugin_name; + Widgets::Plugin* plugin_ptr = nullptr; + std::string event_status; + for (const auto& plugin_instance_id : userprefs.childGroups()) { + userprefs.beginGroup(plugin_instance_id); + plugin_name = userprefs.value("library").value(); + this->loadWidget(plugin_name, plugin_ptr); + // Load the settings + userprefs.beginGroup("standardParams"); + plugin_ptr->loadParameterSettings(userprefs); + userprefs.endGroup(); // standardParams + userprefs.beginGroup("customParams"); + plugin_ptr->loadCustomParameterSettings(userprefs); + userprefs.endGroup(); // customParams + userprefs.endGroup(); // plugin_instance_id + block_cache[plugin_instance_id.toUInt()] = plugin_ptr->getBlock(); + } + userprefs.endGroup(); // Widgets +} + +void MainWindow::saveConnectionSettings(QSettings& userprefs) +{ Event::Object all_connections_event( Event::Type::IO_ALL_CONNECTIONS_QUERY_EVENT); event_manager->postEvent(&all_connections_event); @@ -542,9 +697,9 @@ void MainWindow::saveWidgetSettings(QSettings& userprefs) userprefs.beginGroup("Connections"); int connection_count = 0; for (const auto& conn : connections) { - // NOTE: We don't handle connections that are managed by plugins themselves. - // Namely connections related to probes from oscilloscope and recorders from - // the recorder plugin + // NOTE: We don't handle connections that are managed by plugins + // themselves. Namely connections related to probes from oscilloscope and + // recorders from the recorder plugin if (conn.dest->getName().find("Probe") != std::string::npos || conn.dest->getName().find("Recording") != std::string::npos) { @@ -561,29 +716,9 @@ void MainWindow::saveWidgetSettings(QSettings& userprefs) userprefs.endGroup(); // Connections } -void MainWindow::loadWidgetSettings(QSettings& userprefs) +void MainWindow::loadConnectionSettings( + QSettings& userprefs, std::unordered_map block_cache) { - ///////////////////// Load Widget parameters //////////////////////// - std::unordered_map blocks; - userprefs.beginGroup("Widgets"); - QString plugin_name; - Widgets::Plugin* plugin_ptr = nullptr; - std::string event_status; - for (const auto& plugin_instance_id : userprefs.childGroups()) { - userprefs.beginGroup(plugin_instance_id); - plugin_name = userprefs.value("library").value(); - this->loadWidget(plugin_name, plugin_ptr); - // Load the settings - userprefs.beginGroup("standardParams"); - plugin_ptr->loadParameterSettings(userprefs); - userprefs.endGroup(); // standardParams - userprefs.beginGroup("customParams"); - plugin_ptr->loadCustomParameterSettings(userprefs); - userprefs.endGroup(); // customParams - userprefs.endGroup(); // plugin_instance_id - blocks[plugin_instance_id.toUInt()] = plugin_ptr->getBlock(); - } - userprefs.endGroup(); // Widgets ///////////////////// Load connections ///////////////////////// RT::block_connection_t connection; std::vector connection_events; @@ -591,19 +726,19 @@ void MainWindow::loadWidgetSettings(QSettings& userprefs) userprefs.beginGroup("Connections"); for (const auto& conn_count : userprefs.childKeys()) { id_connection = userprefs.value(conn_count).value(); - if (blocks.find(id_connection.src_id) == blocks.end() - || blocks.find(id_connection.dest_id) == blocks.end()) + if (block_cache.find(id_connection.src_id) == block_cache.end() + || block_cache.find(id_connection.dest_id) == block_cache.end()) { ERROR_MSG( "MainWindow::loadWidgetSettings : invalid connection found. " "Skipping"); continue; } - connection.src = blocks[id_connection.src_id]; + connection.src = block_cache[id_connection.src_id]; connection.src_port_type = static_cast(id_connection.src_direction); connection.src_port = id_connection.src_port; - connection.dest = blocks[id_connection.dest_id]; + connection.dest = block_cache[id_connection.dest_id]; connection.dest_port = id_connection.dest_port; connection_events.emplace_back(Event::Type::IO_LINK_INSERT_EVENT); connection_events.back().setParam("connection", std::any(connection)); @@ -633,11 +768,14 @@ void MainWindow::loadSettings() mdiArea->closeAllSubWindows(); userprefs.beginGroup(profile); + std::unordered_map blocks; this->loadPeriodSettings(userprefs); - this->loadDAQSettings(userprefs); + this->loadDAQSettings(userprefs, blocks); + + this->loadWidgetSettings(userprefs, blocks); - this->loadWidgetSettings(userprefs); + this->loadConnectionSettings(userprefs, blocks); userprefs.endGroup(); // profile userprefs.endGroup(); // workspaces diff --git a/src/main_window.hpp b/src/main_window.hpp index d28a439c8..fc3fff5f7 100644 --- a/src/main_window.hpp +++ b/src/main_window.hpp @@ -23,6 +23,7 @@ #include #include + #include "event.hpp" class QSettings; @@ -33,9 +34,15 @@ class QMenu; class QTextEdit; class QTextItem; -namespace Widgets{ +namespace Widgets +{ class Plugin; -} // namespace Widgets +} // namespace Widgets + +namespace IO +{ +class Block; +} // namespace IO class SaveSettingsDialog : public QDialog { @@ -165,13 +172,19 @@ private slots: private: void loadWidget(const QString& module_name); - void loadWidget(const QString& module_name, Widgets::Plugin*& rtxi_plugin_pointer); + void loadWidget(const QString& module_name, + Widgets::Plugin*& rtxi_plugin_pointer); inline void savePeriodSettings(QSettings& userprefs); inline void loadPeriodSettings(QSettings& userprefs); inline void saveDAQSettings(QSettings& userprefs); - inline void loadDAQSettings(QSettings& userprefs); + inline void loadDAQSettings( + QSettings& userprefs, std::unordered_map block_cache); inline void saveWidgetSettings(QSettings& userprefs); - inline void loadWidgetSettings(QSettings& userprefs); + inline void loadWidgetSettings( + QSettings& userprefs, std::unordered_map block_cache); + inline void saveConnectionSettings(QSettings& userprefs); + inline void loadConnectionSettings( + QSettings& userprefs, std::unordered_map block_cache); Event::Manager* event_manager; QMdiArea* mdiArea = nullptr; QList subWindows; From b9aee2abdbf40a5b2b9ae7863dfaf263770883d1 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Mon, 7 Oct 2024 01:23:36 -0400 Subject: [PATCH 31/36] Minor fix to forward declaration of task struct --- src/rt.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rt.hpp b/src/rt.hpp index d3fe3f0e7..755f212b7 100644 --- a/src/rt.hpp +++ b/src/rt.hpp @@ -29,7 +29,7 @@ namespace RT::OS { -class Task; +struct Task; class Fifo; } // namespace RT::OS From 244288a8c19aa15aed0b27be53c4de09d8956e92 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 12 Oct 2024 13:00:52 -0400 Subject: [PATCH 32/36] Removed some clang-tidy checks that are not relevant to the RTXI project --- .clang-tidy | 23 +++++++---------------- 1 file changed, 7 insertions(+), 16 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index d354b9d34..9a6e3b8f0 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -1,41 +1,32 @@ --- -# Enable ALL the things! Except not really -# misc-non-private-member-variables-in-classes: the options don't do anything +# Enable relevant things! +# cpp core guidelines is our main check that we try to follow as close as possible. +# The following are disabled checks becuase they don't make any sesne for our +# project: # readability-identifier-naming: Should be enabled after main refactoring is done # *-vararg: we are dealing with variable argument c functions. cannot be helped # -modernize-deprecated-headers: dealing with c headers # -modernize-use-nodiscard: We are dealing with legacy code so this is too much. # -modernize-use-using: Conflicts with another warning. -# -hicpp-signed-bitwise: There are c functions that will fire this warning. bye bye. # -cppcoreguidelines-owning-memory: Qt uses parent widget relationships. # -readability-identifier-nanme: shorter names can make sense in some cases. # -cppcoreguidelines-avoid-magic-numbers: Qt design is littered with these unfortunately. # -readability-magic-numbers: Same reason as above - cannot be helped due to Qt # -readability-redundant-access-specifiers: Qt's slot specifier produces this warning -# -abseil-string-find-str-contains: we don't use abseil strings in this project -Checks: "*,\ - -abseil-string-find-str-contains,\ +Checks: "bugprone-*, concurrency-*, cppcoreguidelines-*,\ + modernize-*, performance-*, readability-*,\ -readability-redundant-access-specifiers,\ -readability-magic-numbers,\ -cppcoreguidelines-avoid-magic-numbers,\ -readability-identifier-length,\ -cppcoreguidelines-owning-memory,\ - -hicpp-signed-bitwise,\ - -hicpp-deprecated-headers,\ -*-vararg,\ -modernize-deprecated-headers,\ -modernize-use-trailing-return-type,\ -modernize-use-nodiscard,\ -modernize-use-using,\ -google-readability-todo,\ - -readability-identifier-naming,\ - -altera-*,\ - -fuchsia-*,\ - fuchsia-multiple-inheritance,\ - -llvm-header-guard,\ - -llvm-include-order,\ - -llvmlibc-*,\ - -misc-non-private-member-variables-in-classes" + -readability-identifier-naming" WarningsAsErrors: '' CheckOptions: - key: 'bugprone-argument-comment.StrictMode' From 94f469222fddb29bdb44c27d77944118f5960a38 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 12 Oct 2024 21:23:30 -0400 Subject: [PATCH 33/36] Spell-fix pass --- .clang-tidy | 2 +- src/gsc_aio168_driver.cpp | 8 ++++---- src/main_window.cpp | 2 +- src/nidaq_driver.cpp | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 9a6e3b8f0..5d72b3494 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -1,7 +1,7 @@ --- # Enable relevant things! # cpp core guidelines is our main check that we try to follow as close as possible. -# The following are disabled checks becuase they don't make any sesne for our +# The following are disabled checks because they don't make any sesne for our # project: # readability-identifier-naming: Should be enabled after main refactoring is done # *-vararg: we are dealing with variable argument c functions. cannot be helped diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp index b434c73e5..435ccc2b1 100644 --- a/src/gsc_aio168_driver.cpp +++ b/src/gsc_aio168_driver.cpp @@ -328,7 +328,7 @@ Device::Device(const std::string& dev_name, } // We need to tell the board that channel scanning is software timed. - // Check 16aio168 manual for explenation of this setting + // Check 16aio168 manual for explanation of this setting int32_t scan_setting = AIO168_AI_SCAN_CLK_SRC_BCR; result = aio168_ioctl(fd, AIO168_IOCTL_AI_SCAN_CLK_SRC, &scan_setting); if (result < 0) { @@ -350,7 +350,7 @@ Device::Device(const std::string& dev_name, //result = aio168_ioctl(fd, AIO168_IOCTL_AO_TIMING, &timing); //if (result < 0) { // ERROR_MSG( - // "16QIO168 DRIVER : Unable to set the channel sync to simultanous output " + // "16QIO168 DRIVER : Unable to set the channel sync to simultaneous output " // "for device"); // printError(result); //} @@ -711,7 +711,7 @@ void Device::write() ao_channels_buffer.back() |= 1 << 19; aio168_write( fd, ao_channels_buffer.data(), ao_channels_buffer.size() * sizeof(int32_t)); - // initate output sync + // initiate output sync // aio168_ioctl(fd, AIO168_IOCTL_AO_SYNC, nullptr); } @@ -730,7 +730,7 @@ Driver::Driver() throw std::runtime_error(fmt::format( "DAQ::16aio168 : {} does not exist! Cannot discover driver information \n{}", device_info_file, - "Make sure that the 16aio168 module is loaded before continuing. You can do this by runnign ./script in the driver directory.")); + "Make sure that the 16aio168 module is loaded before continuing. You can do this by running ./script in the driver directory.")); } // Parse Driver Information std::ifstream file_stream(device_info_file); diff --git a/src/main_window.cpp b/src/main_window.cpp index c6cf2087c..40e303328 100644 --- a/src/main_window.cpp +++ b/src/main_window.cpp @@ -500,7 +500,7 @@ void MainWindow::saveDAQSettings(QSettings& userprefs) "active", device->getChannelActive(DAQ::ChannelType::DI, di_channel)); userprefs.endGroup(); } - userprefs.endGroup(); // Digitial Input + userprefs.endGroup(); // Digital Input userprefs.beginGroup("DO"); for (size_t do_channel = 0; do_channel < device->getChannelCount(DAQ::ChannelType::DO); diff --git a/src/nidaq_driver.cpp b/src/nidaq_driver.cpp index 8fff9b87e..b304e9b6d 100644 --- a/src/nidaq_driver.cpp +++ b/src/nidaq_driver.cpp @@ -391,7 +391,7 @@ class Device final : public DAQ::Device std::array default_units = DAQ::get_default_units(); // Used a tuple here because we want buffers to be in one place, and since not all - // IO is flaot, that meant we could not use a plain vector of vectors. Maybe we can + // IO is float, that meant we could not use a plain vector of vectors. Maybe we can // just split them out to their own variables of same type for speed. std::tuple, std::vector, From 2979315bb8c44eab0c8ac53dfc66366d939cb890 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 12 Oct 2024 21:25:46 -0400 Subject: [PATCH 34/36] Fix mispelling in workspace.hpp doc comment --- src/workspace.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/workspace.hpp b/src/workspace.hpp index 20fe5894a..5af6a3729 100644 --- a/src/workspace.hpp +++ b/src/workspace.hpp @@ -78,7 +78,7 @@ class Manager : public Event::Handler void unloadPlugin(Widgets::Plugin* plugin); /*! - * Handles plugin loading/unloadin gevents from gui thread + * Handles plugin loading/unloading gevents from gui thread * * \param event The event to handle. The workspace manager only handles the * following event types: Event::Type::PLUGIN_INSERT_EVENT From 28c75fd55077a3397a6af516d8eff8edd949711d Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 12 Oct 2024 21:27:52 -0400 Subject: [PATCH 35/36] format-fix pass --- plugins/data_recorder/data_recorder.cpp | 10 ++-- plugins/system_control/system_control.cpp | 4 +- src/event.hpp | 2 +- src/gsc_aio168_driver.cpp | 69 +++++++++++++---------- src/logger.hpp | 5 +- src/nidaq_driver.cpp | 22 ++++---- src/rt.cpp | 6 +- src/workspace.cpp | 3 +- src/workspace.hpp | 15 +++-- test/system_tests.cpp | 1 + 10 files changed, 78 insertions(+), 59 deletions(-) diff --git a/plugins/data_recorder/data_recorder.cpp b/plugins/data_recorder/data_recorder.cpp index a73eb1927..6f19e8963 100644 --- a/plugins/data_recorder/data_recorder.cpp +++ b/plugins/data_recorder/data_recorder.cpp @@ -19,16 +19,16 @@ #include #include +#include +#include +#include #include +#include #include +#include #include #include #include -#include -#include -#include -#include -#include #include #include diff --git a/plugins/system_control/system_control.cpp b/plugins/system_control/system_control.cpp index 408a2bae7..327605500 100644 --- a/plugins/system_control/system_control.cpp +++ b/plugins/system_control/system_control.cpp @@ -21,18 +21,18 @@ #include #include #include +#include #include #include -#include #include #include #include "system_control.hpp" #include "daq.hpp" +#include "event.hpp" #include "rt.hpp" #include "rtos.hpp" -#include "event.hpp" SystemControl::Panel::Panel(QMainWindow* mw, Event::Manager* ev_manager) : Widgets::Panel(std::string(SystemControl::MODULE_NAME), mw, ev_manager) diff --git a/src/event.hpp b/src/event.hpp index b5a569382..1a3749b75 100644 --- a/src/event.hpp +++ b/src/event.hpp @@ -72,7 +72,7 @@ enum Type IO_LINK_REMOVE_EVENT, IO_BLOCK_QUERY_EVENT, IO_BLOCK_OUTPUTS_QUERY_EVENT, - IO_CONNECTION_QUERY_EVENT, // TODO: Implement for connector + IO_CONNECTION_QUERY_EVENT, // TODO: Implement for connector IO_ALL_CONNECTIONS_QUERY_EVENT, PLUGIN_INSERT_EVENT, PLUGIN_REMOVE_EVENT, diff --git a/src/gsc_aio168_driver.cpp b/src/gsc_aio168_driver.cpp index 435ccc2b1..8072ad11d 100644 --- a/src/gsc_aio168_driver.cpp +++ b/src/gsc_aio168_driver.cpp @@ -338,22 +338,22 @@ Device::Device(const std::string& dev_name, printError(result); } - //int32_t sync_setting = AIO168_AO_BURST_CLK_SRC_BCR; - //result = aio168_ioctl(fd, AIO168_IOCTL_AO_BURST_CLK_SRC, &sync_setting); - //if (result < 0) { - // ERROR_MSG( - // "16QIO168 DRIVER : Unable to set the channel sync to software trigger " - // "for device"); - // printError(result); - //} - //int32_t timing = AIO168_AO_TIMING_SIMUL; - //result = aio168_ioctl(fd, AIO168_IOCTL_AO_TIMING, &timing); - //if (result < 0) { - // ERROR_MSG( - // "16QIO168 DRIVER : Unable to set the channel sync to simultaneous output " - // "for device"); - // printError(result); - //} + // int32_t sync_setting = AIO168_AO_BURST_CLK_SRC_BCR; + // result = aio168_ioctl(fd, AIO168_IOCTL_AO_BURST_CLK_SRC, &sync_setting); + // if (result < 0) { + // ERROR_MSG( + // "16QIO168 DRIVER : Unable to set the channel sync to software trigger + // " "for device"); + // printError(result); + // } + // int32_t timing = AIO168_AO_TIMING_SIMUL; + // result = aio168_ioctl(fd, AIO168_IOCTL_AO_TIMING, &timing); + // if (result < 0) { + // ERROR_MSG( + // "16QIO168 DRIVER : Unable to set the channel sync to simultaneous + // output " "for device"); + // printError(result); + // } ai_channels_buffer.assign(getChannelCount(DAQ::ChannelType::AI), 0); ao_channels_buffer.assign(getChannelCount(DAQ::ChannelType::AO), 0); @@ -367,8 +367,8 @@ Device::Device(const std::string& dev_name, // Don't let the device sleep when reading and just return immediately int32_t timeout = 0; result = aio168_ioctl(fd, AIO168_IOCTL_RX_IO_TIMEOUT, &timeout); - //timeout = 0; - //result = aio168_ioctl(fd, AIO168_IOCTL_TX_IO_TIMEOUT, &timeout); + // timeout = 0; + // result = aio168_ioctl(fd, AIO168_IOCTL_TX_IO_TIMEOUT, &timeout); this->setActive(/*act=*/true); } @@ -396,16 +396,20 @@ int Device::setChannelActive(DAQ::ChannelType::type_t type, active_channels.at(type).end(), static_cast(index)); physical_channels_registry.at(type).at(index).active = state; - if(state){ - if(iter == active_channels.at(type).end()) { active_channels.at(type).push_back(static_cast(index)); } + if (state) { + if (iter == active_channels.at(type).end()) { + active_channels.at(type).push_back(static_cast(index)); + } } else { - if(iter != active_channels.at(type).end()) { active_channels.at(type).erase(iter); } + if (iter != active_channels.at(type).end()) { + active_channels.at(type).erase(iter); + } } if (type != DAQ::ChannelType::AI) { return 0; } - if(active_channels.at(type).empty()) { + if (active_channels.at(type).empty()) { CURRENT_SCAN_SIZE = 0; return 0; } @@ -683,7 +687,9 @@ void Device::read() // we have to convert some stuff to float first before we continue for (size_t chan_id = 0; chan_id < CURRENT_SCAN_SIZE; chan_id++) { auto& chan_info = physical_channels_registry[DAQ::ChannelType::AI][chan_id]; - if(!chan_info.active) { continue; } + if (!chan_info.active) { + continue; + } range = default_ranges[chan_info.range_index]; gain = chan_info.gain; offset = chan_info.offset; @@ -705,12 +711,15 @@ void Device::write() range = default_ranges[chan_info.range_index]; gain = chan_info.gain; offset = chan_info.offset; - value = std::min(std::max(readinput(chan_id) * gain + offset, range.first), range.second); - ao_channels_buffer[chan_id] = voltage_to_binary(range, value) | chan_id << 16; + value = std::min(std::max(readinput(chan_id) * gain + offset, range.first), + range.second); + ao_channels_buffer[chan_id] = + voltage_to_binary(range, value) | chan_id << 16; } ao_channels_buffer.back() |= 1 << 19; - aio168_write( - fd, ao_channels_buffer.data(), ao_channels_buffer.size() * sizeof(int32_t)); + aio168_write(fd, + ao_channels_buffer.data(), + ao_channels_buffer.size() * sizeof(int32_t)); // initiate output sync // aio168_ioctl(fd, AIO168_IOCTL_AO_SYNC, nullptr); } @@ -728,9 +737,11 @@ Driver::Driver() if (!std::filesystem::exists(device_info_file)) { printError(result); throw std::runtime_error(fmt::format( - "DAQ::16aio168 : {} does not exist! Cannot discover driver information \n{}", + "DAQ::16aio168 : {} does not exist! Cannot discover driver information " + "\n{}", device_info_file, - "Make sure that the 16aio168 module is loaded before continuing. You can do this by running ./script in the driver directory.")); + "Make sure that the 16aio168 module is loaded before continuing. You " + "can do this by running ./script in the driver directory.")); } // Parse Driver Information std::ifstream file_stream(device_info_file); diff --git a/src/logger.hpp b/src/logger.hpp index adbf3123f..a124ad5f1 100644 --- a/src/logger.hpp +++ b/src/logger.hpp @@ -7,9 +7,10 @@ #include "rt.hpp" -namespace Event{ +namespace Event +{ class Object; -} // namespace Event +} // namespace Event /*! * Class responsible for logging all events and telemitry diff --git a/src/nidaq_driver.cpp b/src/nidaq_driver.cpp index b304e9b6d..6fd544b68 100644 --- a/src/nidaq_driver.cpp +++ b/src/nidaq_driver.cpp @@ -370,18 +370,19 @@ class Device final : public DAQ::Device void write() final; private: - // RTXI uses 4 tasks, each with it's own different type: AI, AO, DI, DO. This is - // not our choice... it is required by NIDAQmx to get things going + // RTXI uses 4 tasks, each with it's own different type: AI, AO, DI, DO. This + // is not our choice... it is required by NIDAQmx to get things going std::array task_list {}; - // NIDAQmx channels are NOT the same as IO::Block channels used by RTXI. For example AI channels - // on NIDAQmx are physically entering the machine, but they are seen as output signals - // from the DAQ IO block in the read phase. + // NIDAQmx channels are NOT the same as IO::Block channels used by RTXI. For + // example AI channels on NIDAQmx are physically entering the machine, but + // they are seen as output signals from the DAQ IO block in the read phase. std::array, DAQ::ChannelType::UNKNOWN> active_channels; - // NIDAQmx will assign a unique name related to discovery order. Something like - // Dev1, Dev2, etc and two cards of the same type can be accessed with this. + // NIDAQmx will assign a unique name related to discovery order. Something + // like Dev1, Dev2, etc and two cards of the same type can be accessed with + // this. std::string internal_dev_name; // Some defaults that we don't bother providing flexibility for even though @@ -390,9 +391,10 @@ class Device final : public DAQ::Device std::array default_ranges = DAQ::get_default_ranges(); std::array default_units = DAQ::get_default_units(); - // Used a tuple here because we want buffers to be in one place, and since not all - // IO is float, that meant we could not use a plain vector of vectors. Maybe we can - // just split them out to their own variables of same type for speed. + // Used a tuple here because we want buffers to be in one place, and since not + // all IO is float, that meant we could not use a plain vector of vectors. + // Maybe we can just split them out to their own variables of same type for + // speed. std::tuple, std::vector, std::vector, diff --git a/src/rt.cpp b/src/rt.cpp index 2a6736649..f1997d0a1 100644 --- a/src/rt.cpp +++ b/src/rt.cpp @@ -44,7 +44,8 @@ int RT::Connector::find_cycle(RT::block_connection_t conn, IO::Block* ref_block) // walk the connection graph and find a loop for (const auto& temp_conn : this->connections[conn.dest->getID()]) { if (ref_block == temp_conn.src - || this->find_cycle(temp_conn, ref_block) == -1) { + || this->find_cycle(temp_conn, ref_block) == -1) + { return -1; } } @@ -327,7 +328,8 @@ void RT::System::createTelemitryProcessor() eventLogger* logger = this->event_manager->getLogger(); std::vector responses; while (!this->task->task_finished - && this->telemitry_processing_thread_running) { + && this->telemitry_processing_thread_running) + { responses = this->getTelemitry(); for (auto telem : responses) { if (telem.cmd != nullptr) { diff --git a/src/workspace.cpp b/src/workspace.cpp index a36e00e4c..0800a213d 100644 --- a/src/workspace.cpp +++ b/src/workspace.cpp @@ -12,12 +12,11 @@ see . */ +#include #include #include "workspace.hpp" -#include - #include "connector/connector.hpp" #include "data_recorder/data_recorder.hpp" #include "dlplugin.hpp" diff --git a/src/workspace.hpp b/src/workspace.hpp index 5af6a3729..4637b5ee8 100644 --- a/src/workspace.hpp +++ b/src/workspace.hpp @@ -19,18 +19,21 @@ #include "widgets.hpp" -namespace Event{ +namespace Event +{ class Object; -} // namespace Event +} // namespace Event -namespace DLL{ +namespace DLL +{ class Loader; -} // namespace DLL +} // namespace DLL -namespace DAQ{ +namespace DAQ +{ class Device; class Driver; -} // namespace DAQ +} // namespace DAQ /*! * Objects contained within this namespace are responsible for providing diff --git a/test/system_tests.cpp b/test/system_tests.cpp index 4c20e4b49..20a6c4e07 100644 --- a/test/system_tests.cpp +++ b/test/system_tests.cpp @@ -24,6 +24,7 @@ #include "system_tests.hpp" #include + #include "rtos.hpp" TEST_F(RTConnectorTest, connections) From 038fb4604f3cdf52ae4dc4e585cd9416295898c6 Mon Sep 17 00:00:00 2001 From: "Ivan F. Valerio" Date: Sat, 12 Oct 2024 21:48:12 -0400 Subject: [PATCH 36/36] Install script modified to use apt instead of snap to install cmake dependency --- scripts/install_dependencies.sh | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/scripts/install_dependencies.sh b/scripts/install_dependencies.sh index 084136064..3b03e2222 100755 --- a/scripts/install_dependencies.sh +++ b/scripts/install_dependencies.sh @@ -37,9 +37,8 @@ apt-get -y install \ build-essential qtbase5-dev qtbase5-dev-tools \ libqwt-qt5-dev libqt5svg5-dev libhdf5-dev \ libgsl-dev libgtest-dev libgmock-dev libfmt-dev vim lshw stress \ - binutils-dev zstd git \ + binutils-dev zstd git cmake\ crash kexec-tools makedumpfile kernel-wedge libncurses5-dev libelf-dev \ flex bison pkgconf python3-pip ninja-build dwarves -snap install cmake echo "-----> Package dependencies installed." echo "-----> Done."