Browse Source

测试并改进了 transform_stabilizer

jcsyshc 2 years ago
parent
commit
d358ae968f

+ 7 - 1
src/algorithm/measure_window.hpp

@@ -1,9 +1,12 @@
 #ifndef SOPHIAR2_MEASURE_WINDOW_HPP
 #define SOPHIAR2_MEASURE_WINDOW_HPP
 
+#include "utility/dynamic_pool.hpp"
+
 #include <boost/core/noncopyable.hpp>
 
 #include <cmath>
+#include <deque>
 #include <queue>
 
 namespace sophiar {
@@ -70,7 +73,10 @@ namespace sophiar {
         size_t win_length;
         size_t cur_n = 0;
         double sum_x = 0, sum_x2 = 0;
-        std::queue<double> win;
+
+        using dynamic_deque = std::deque<double, DYNAMIC_ALLOCATOR(double) >;
+        using dynamic_queue = std::queue<double, dynamic_deque>;
+        dynamic_queue win;
 
     };
 

+ 106 - 87
src/algorithm/transform_stabilizer.cpp

@@ -1,12 +1,16 @@
-#include "transform_stabilizer.h"
-
 #include "algorithm/measure_window.hpp"
 #include "core/basic_obj_types.hpp"
+#include "core/global_defs.h"
+#include "core/tristate_obj.h"
 #include "utility/bit_operations.hpp"
+#include "utility/config_utility.hpp"
 #include "utility/coro_worker.hpp"
+#include "utility/variable_helper.hpp"
 
 #include <Eigen/Geometry>
 
+DEFAULT_TRISTATE_OBJ_DEF(transform_stabilizer)
+
 namespace sophiar {
 
     using boost::asio::awaitable;
@@ -19,20 +23,22 @@ namespace sophiar {
         static constexpr double default_angular_tolerance_deg = 0.05;
 
         bool stable_point_only = true; // 是否仅稳定一个点
-        double linear_tolerance = 0.0002; // 0.2 mm
-        double angular_tolerance = 0.01; // 0.01 rad
+        double linear_tolerance = 0.02; // 0.2 mm
+        double angular_tolerance = 0.0002; // ≈ 0.01 deg
 
         bool use_temporal_interval = true; // 使用基于时间长度的窗长控制
         timestamp_type temporal_interval = 1500000; // 1.5s
-        timestamp_type counting_start_ts = 0, last_sample_ts = 0;
         size_t counting_interval = 150;
 
         measure_window pos_win[3];
         measure_window ang_win[3];
         measure_window qua_win[4];
 
-        global_obj_index_type input_obj_index = invalid_global_obj_index;
-        global_obj_index_type output_obj_index = invalid_global_obj_index;
+        using dynamic_ts_deque = std::deque<timestamp_type, DYNAMIC_ALLOCATOR(timestamp_type) >;
+        dynamic_ts_deque ts_que;
+
+        variable_index_type input_var_index = invalid_variable_index;
+        variable_index_type output_var_index = invalid_variable_index;
 
         coro_worker::pointer stable_worker;
 
@@ -43,6 +49,7 @@ namespace sophiar {
 
         void reset_windows() {
             ALL_WIN_OP({ win.reset(); })
+            ts_que.clear();
         }
 
         size_t get_cur_length() const {
@@ -92,10 +99,10 @@ namespace sophiar {
             return std::sqrt(std2);
         }
 
-        template<bool UseTemporalInterval>
         bool check_interval_condition() const {
-            if constexpr (UseTemporalInterval) {
-                return last_sample_ts - counting_start_ts >= temporal_interval;
+            if (use_temporal_interval) {
+                if (ts_que.empty()) return false;
+                return ts_que.back() - ts_que.front() >= temporal_interval;
             } else {
                 return get_cur_length() >= counting_interval;
             }
@@ -111,21 +118,19 @@ namespace sophiar {
             return calc_translation_std() <= linear_tolerance;
         }
 
-        template<bool StablePointOnly, bool UseTemporalInterval>
+        template<bool StablePointOnly>
         bool check_stable() const {
-            if (!check_interval_condition<UseTemporalInterval>()) return false;
-            if (!check_translation_condition()) return false;
+            if (!check_interval_condition()) [[likely]] return false;
+            if (!check_translation_condition()) [[likely]] return false;
             if constexpr (!StablePointOnly) {
-                if (!check_rotation_condition()) return false;
+                if (!check_rotation_condition()) [[likely]] return false;
             }
             return true;
         }
 
         void update_sample_ts(timestamp_type ts = current_timestamp()) {
-            if (get_cur_length() == 0) {
-                counting_start_ts = ts;
-            }
-            last_sample_ts = ts;
+            if (!use_temporal_interval) return;
+            ts_que.push_back(ts);
         }
 
         template<typename RotationType>
@@ -159,90 +164,109 @@ namespace sophiar {
             on_new_rotation_sample(trans.rotation());
         }
 
+        void remove_old_translation_sample() {
+            while (check_interval_condition()) {
+                for (auto &win: pos_win) {
+                    win.pop();
+                }
+                if (use_temporal_interval) {
+                    ts_que.pop_front();
+                }
+            }
+        }
+
+        void remove_old_transform_sample() {
+            while (check_interval_condition()) {
+                ALL_WIN_OP({ win.pop(); })
+                if (use_temporal_interval) {
+                    ts_que.pop_front();
+                }
+            }
+        }
+
         void on_point_stabled() const {
             auto trans_result = get_translation();
             auto ret = scalarxyz_obj::new_instance();
             ret->value.x() = trans_result.x();
             ret->value.y() = trans_result.y();
             ret->value.z() = trans_result.z();
-            UPDATE_GLOBAL_OBJ(scalarxyz_obj, output_obj_index, ret);
+            UPDATE_VARIABLE(scalarxyz_obj, output_var_index, ret);
         }
 
         void on_transform_stabled() const {
             auto trans_result = get_transform();
             auto ret = transform_obj::new_instance();
             ret->value = trans_result;
-            UPDATE_GLOBAL_OBJ(transform_obj, output_obj_index, ret);
+            UPDATE_VARIABLE(transform_obj, output_var_index, ret);
         }
 
         template<bool StablePointOnly>
-        void on_stabled() const {
-            assert(is_valid_id(output_obj_index));
+        void on_stabled() {
+            assert(is_valid_id(output_var_index));
             if constexpr (StablePointOnly) {
                 on_point_stabled();
             } else {
                 on_transform_stabled();
             }
+            reset_windows();
         }
 
-        template<bool StablePointOnly, bool UseTemporalInterval>
-        coro_worker::pointer create_worker_impl() {
+        auto create_stable_point_only_worker() {
+            static constexpr bool StablePointOnly = true;
             auto func = [this,
-                    watcher = NEW_GLOBAL_OBJ_WATCHER(input_obj_index)]() mutable
+                    point = VARIABLE_MANUAL_DELEGATE(scalarxyz_obj, input_var_index)]() mutable
                     -> awaitable<bool> {
-                co_await watcher.coro_wait(false);
-                auto update_ts = GLOBAL_OBJ_UPDATE_TS(input_obj_index);
-                if constexpr (StablePointOnly) {
-                    auto point = GET_GLOBAL_OBJ(scalarxyz_obj, input_obj_index);
-                    if (point == nullptr) {
-                        reset_windows();
-                    } else {
-                        if constexpr (UseTemporalInterval) {
-                            update_sample_ts(update_ts);
-                        }
-                        on_new_translation_sample(point->value);
-                    }
+                co_await point.coro_wait_update();
+                auto update_ts = point.get_last_update_ts();
+                if (point.empty()) {
+                    reset_windows();
                 } else {
-                    auto trans = GET_GLOBAL_OBJ(transform_obj, input_obj_index);
-                    if (trans == nullptr) {
-                        reset_windows();
-                    } else {
-                        if constexpr (UseTemporalInterval) {
-                            update_sample_ts(update_ts);
-                        }
-                        on_new_transform_sample(trans->value);
-                    }
+                    update_sample_ts(update_ts);
+                    on_new_translation_sample(point->value);
                 }
-                if (check_stable<StablePointOnly, UseTemporalInterval>()) [[unlikely]] {
+                if (check_stable<StablePointOnly>()) [[unlikely]] {
                     on_stabled<StablePointOnly>();
                 }
+                remove_old_translation_sample();
                 co_return true;
             };
-            return make_infinite_coro_worker(get_context(), std::move(func));
+            return make_infinite_coro_worker(std::move(func));
         }
 
-        void create_worker() {
-            assert(stable_worker == nullptr);
-            if (stable_point_only) {
-                if (use_temporal_interval) {
-                    stable_worker = create_worker_impl<true, true>();
+        auto create_stable_transform_worker() {
+            static constexpr bool StablePointOnly = false;
+            auto func = [this,
+                    trans = VARIABLE_MANUAL_DELEGATE(transform_obj, input_var_index)]() mutable
+                    -> awaitable<bool> {
+                co_await trans.coro_wait_update();
+                auto update_ts = trans.get_last_update_ts();
+                if (trans.empty()) {
+                    reset_windows();
+                    co_return true;
                 } else {
-                    stable_worker = create_worker_impl<true, false>();
+                    update_sample_ts(update_ts);
+                    on_new_transform_sample(trans->value);
                 }
-            } else {
-                if (use_temporal_interval) {
-                    stable_worker = create_worker_impl<false, true>();
-                } else {
-                    stable_worker = create_worker_impl<false, false>();
+                if (check_stable<StablePointOnly>()) [[unlikely]] {
+                    on_stabled<StablePointOnly>();
                 }
-            }
+                remove_old_transform_sample();
+                co_return true;
+            };
+            return make_infinite_coro_worker(std::move(func));
+        }
+
+        void create_worker() {
+            assert(stable_worker == nullptr);
+            stable_worker = stable_point_only ?
+                            create_stable_point_only_worker() :
+                            create_stable_transform_worker();
             stable_worker->run();
         }
 
         void load_config(const nlohmann::json &config) {
             // stable type
-            assert(config.contains("stable_type"));
-            assert(config["stable_type"].is_string());
+            ENSURE_STRING("stable_type");
             if (config["stable_type"] == "transform") {
                 stable_point_only = false;
             } else {
@@ -251,36 +275,30 @@ namespace sophiar {
             }
 
             // I/O
-            assert(config.contains("input_obj_name"));
-            assert(config.contains("output_obj_name"));
-            assert(config["input_obj_name"].is_string());
-            assert(config["output_obj_name"].is_string());
-            auto input_obj_name = config["input_obj_name"].get<std::string>();
-            auto output_obj_name = config["output_obj_name"].get<std::string>();
+            auto input_var_name = LOAD_STRING_ITEM("input_var_name");
+            auto output_var_name = LOAD_STRING_ITEM("output_var_name");
             if (stable_point_only) {
-                input_obj_index = REGISTER_GLOBAL_OBJ(scalarxyz_obj, input_obj_name);
-                output_obj_index = REGISTER_GLOBAL_OBJ(scalarxyz_obj, output_obj_name);
+                input_var_index = REQUIRE_VARIABLE(scalarxyz_obj, input_var_name);
+                output_var_index = REQUIRE_VARIABLE(scalarxyz_obj, output_var_name);
             } else {
-                input_obj_index = REGISTER_GLOBAL_OBJ(transform_obj, input_obj_name);
-                output_obj_index = REGISTER_GLOBAL_OBJ(transform_obj, output_obj_name);
+                input_var_index = REQUIRE_VARIABLE(transform_obj, input_var_name);
+                output_var_index = REQUIRE_VARIABLE(transform_obj, output_var_name);
             }
 
             // linear tolerance
             double linear_tolerance_mm = default_linear_tolerance_mm;
             if (config.contains("linear_tolerance_mm")) {
-                assert(config["linear_tolerance_mm"].is_number());
-                linear_tolerance_mm = config["linear_tolerance_mm"].get<double>();
+                linear_tolerance_mm = LOAD_FLOAT_ITEM("linear_tolerance_mm");
             } else {
                 // TODO show log, use default value
             }
-            linear_tolerance = linear_tolerance_mm * 1000.0; // mm -> m
+            linear_tolerance = linear_tolerance_mm;
 
             // angular tolerance
             if (!stable_point_only) {
                 double angular_tolerance_deg = default_angular_tolerance_deg;
                 if (config.contains("angular_tolerance_deg")) {
-                    assert(config["angular_tolerance_deg"].is_number());
-                    angular_tolerance_deg = config["angular_tolerance_deg"].get<double>();
+                    angular_tolerance_deg = LOAD_FLOAT_ITEM("angular_tolerance_deg");
                 } else {
                     // TODO show log, use default value
                 }
@@ -289,39 +307,40 @@ namespace sophiar {
 
             // interval
             if (config.contains("temporal_interval_s")) {
-                assert(config["temporal_interval_s"].is_number());
                 use_temporal_interval = true;
-                auto temporal_interval_s = config["temporal_interval_s"].get<double>();
-                temporal_interval = temporal_interval_s * 1000000; // s -> us
+                temporal_interval = LOAD_FLOAT_ITEM("temporal_interval_s") * 1000000;
             } else {
-                assert(config.contains("counting_interval"));
-                assert(config["counting_interval"].is_number_unsigned());
                 use_temporal_interval = false;
-                counting_interval = config["counting_interval"].get<uint64_t>();
+                counting_interval = LOAD_UINT_ITEM("counting_interval");
             }
         }
 
     };
 
-    awaitable<bool> transform_stabilizer::on_init(const nlohmann::json &config) {
+    transform_stabilizer::transform_stabilizer()
+            : pimpl(std::make_unique<impl>()) {}
+
+    transform_stabilizer::~transform_stabilizer() = default;
+
+    awaitable<bool> transform_stabilizer::on_init(const nlohmann::json &config) noexcept {
         co_return true;
     }
 
-    awaitable<bool> transform_stabilizer::on_start(const nlohmann::json &config) {
+    awaitable<bool> transform_stabilizer::on_start(const nlohmann::json &config) noexcept {
         pimpl->load_config(config);
         pimpl->reset_windows();
         pimpl->create_worker();
         co_return true;
     }
 
-    awaitable<void> transform_stabilizer::on_stop() {
+    awaitable<void> transform_stabilizer::on_stop() noexcept {
         pimpl->stable_worker->cancel();
         co_await pimpl->stable_worker->coro_wait_stop();
         pimpl->stable_worker = nullptr;
         co_return;
     }
 
-    awaitable<void> transform_stabilizer::on_reset() {
+    awaitable<void> transform_stabilizer::on_reset() noexcept {
         co_return;
     }
 

+ 0 - 8
src/algorithm/transform_stabilizer.h

@@ -1,8 +0,0 @@
-#ifndef SOPHIAR2_TRANSFORM_STABILIZER_H
-#define SOPHIAR2_TRANSFORM_STABILIZER_H
-
-#include "core/tristate_obj.h"
-
-DEFAULT_TRISTATE_OBJ_DEF(transform_stabilizer)
-
-#endif //SOPHIAR2_TRANSFORM_STABILIZER_H

+ 1 - 5
src/robot/ur/ur_interface.cpp

@@ -877,11 +877,7 @@ namespace sophiar {
         awaitable<void> on_stop_impl() {
             // stop sending command
             if (current_control_mode != control_mode_type::NO_CONTROL) {
-                if (command_worker != nullptr) {
-                    command_worker->cancel();
-                    co_await command_worker->coro_wait_stop();
-                    command_worker = nullptr;
-                }
+                SAFE_RESET_WORKER(command_worker)
             } else {
                 assert(command_worker == nullptr);
             }

+ 3 - 7
src/tracker/ndi/ndi_interface.cpp

@@ -688,7 +688,7 @@ namespace sophiar {
                 info.last_frame_number = frame_number;
 
                 auto new_trans = transform_obj::new_instance();
-                new_trans->value = Eigen::Quaterniond(q0, qx, qy, qz) * Eigen::Translation3d(tx, ty, tz);
+                new_trans->value = Eigen::Translation3d(tx, ty, tz) * Eigen::Quaterniond(q0, qx, qy, qz);
                 try_update_variable<transform_obj>(info.transform_var_index, std::move(new_trans), ts);
                 try_update_variable_value<double_obj>(info.rms_var_index, rms, ts);
 
@@ -801,9 +801,7 @@ namespace sophiar {
                     co_await stop_stream(get_suitable_bx());
                     stream_reply_callback_pool.clear();
                 } else {
-                    tracking_tools_worker->cancel();
-                    co_await tracking_tools_worker->coro_wait_stop();
-                    tracking_tools_worker = nullptr;
+                    SAFE_RESET_WORKER(tracking_tools_worker)
                 }
                 co_await stop_ndi_tracking();
             } catch (std::exception &e) {
@@ -814,9 +812,7 @@ namespace sophiar {
 
         awaitable<void> on_reset_impl() {
             // stop receiving reply
-            receive_reply_worker->cancel();
-            co_await receive_reply_worker->coro_wait_stop();
-            receive_reply_worker = nullptr;
+            SAFE_RESET_WORKER(receive_reply_worker)
 
             // delete connections
             ndi_tcp_socket.reset(nullptr);

+ 7 - 0
src/utility/coro_worker_helper_func.hpp

@@ -44,4 +44,11 @@ namespace sophiar {
     }
 }
 
+#define SAFE_RESET_WORKER(worker_ptr) \
+    if (worker_ptr != nullptr) { \
+        worker_ptr->cancel(); \
+        co_await worker_ptr->coro_wait_stop(); \
+        worker_ptr = nullptr; \
+    }
+
 #endif //SOPHIAR2_CORO_WORKER_HELPER_FUNC_HPP

+ 4 - 2
tests/CMakeLists.txt

@@ -37,10 +37,12 @@ target_compile_definitions(test_robot PUBLIC SOPHIAR_TEST SOPHIAR_TEST_ROBOT)
 target_compile_definitions(test_robot PUBLIC CORO_SIGNAL2_USE_TIMER)
 target_link_libraries(test_robot ${Boost_LIBRARIES} ${EXTRA_LIBS})
 
+file(GLOB_RECURSE TEST_NDI_SRC_FILES ./interface/ndi*.cpp)
 add_executable(test_ndi
-        ./interface/ndi.cpp
+        ${TEST_NDI_SRC_FILES}
         ../src/tracker/ndi/ndi_interface.cpp
+        ${ALGORITHM_IMPL_FILES}
         ${CORE_IMPL_FILES})
-target_compile_definitions(test_ndi PUBLIC SOPHIAR_TEST SOPHIAR_TEST_NDI)
+target_compile_definitions(test_ndi PUBLIC SOPHIAR_TEST SOPHIAR_TEST_NDI SOPHIAR_TEST_ALGORITHM)
 #target_compile_definitions(test_ndi PUBLIC CORO_SIGNAL2_USE_TIMER)
 target_link_libraries(test_ndi ${Boost_LIBRARIES} ${EXTRA_LIBS})

+ 123 - 0
tests/data/ndi_stabilizer_config.json

@@ -0,0 +1,123 @@
+{
+  "controller_port": 5277,
+  "variable_list": [
+    {
+      "name": "probe_in_tracker",
+      "type": "transform_obj"
+    },
+    {
+      "name": "probe_uncertainty",
+      "type": "double_obj"
+    },
+    {
+      "name": "tip_in_tracker",
+      "type": "scalarxyz_obj"
+    },
+    {
+      "name": "picked_tip_in_tracker",
+      "type": "scalarxyz_obj"
+    },
+    {
+      "name": "picked_probe_in_tracker",
+      "type": "transform_obj"
+    }
+  ],
+  "object_list": [
+    {
+      "type": "ndi_interface",
+      "name": "ndi",
+      "init_config": {
+        "address_type": "ethernet",
+        "ip": "169.254.132.51",
+        "tcp_port": 8765,
+        "com_port": "COM3",
+        "tool_list": [
+          {
+            "rom_path": "D:\\Program\\Robot\\Tools\\roms\\Probe_Small_4Ball.rom",
+            "outputs": {
+              "transform": "probe_in_tracker",
+              "marker_uncertainty": "probe_uncertainty"
+            }
+          }
+        ]
+      },
+      "start_config": {
+        "allow_unreliable": true,
+        "prefer_stream_tracking": true
+      }
+    },
+    {
+      "type": "scalarxyz_transformer",
+      "name": "probe_tip_transformer",
+      "start_config": {
+        "transform_type": "point",
+        "transform_var_name": "probe_in_tracker",
+        "target_value": [
+          -0.02,
+          -0.92,
+          1.54
+        ],
+        "output_var_name": "tip_in_tracker"
+      },
+      "dependencies": [
+        "ndi"
+      ]
+    },
+    {
+      "type": "transform_stabilizer",
+      "name": "point_picker",
+      "start_config": {
+        "stable_type": "point",
+        "input_var_name": "tip_in_tracker",
+        "output_var_name": "picked_tip_in_tracker",
+        "linear_tolerance_mm": 0.02,
+        "angular_tolerance_deg": 0.01,
+        "temporal_interval_s": 1.5,
+        "counting_interval": 150
+      },
+      "dependencies": [
+        "probe_tip_transformer"
+      ]
+    },
+    {
+      "type": "scalarxyz_obj_watcher",
+      "name": "picked_point_watcher",
+      "start_config": {
+        "variable_name": "picked_tip_in_tracker"
+      }
+    },
+    {
+      "type": "transform_stabilizer",
+      "name": "transform_picker",
+      "start_config": {
+        "stable_type": "transform",
+        "input_var_name": "probe_in_tracker",
+        "output_var_name": "picked_probe_in_tracker",
+        "linear_tolerance_mm": 0.02,
+        "angular_tolerance_deg": 0.01,
+        "temporal_interval_s": 3,
+        "counting_interval": 150
+      },
+      "dependencies": [
+        "ndi"
+      ]
+    },
+    {
+      "type": "transform_obj_watcher",
+      "name": "picked_transform_watcher",
+      "start_config": {
+        "variable_name": "picked_probe_in_tracker"
+      }
+    },
+    {
+      "type": "empty_object",
+      "name": "all",
+      "dependencies": [
+        "point_picker",
+        "picked_point_watcher",
+        "transform_picker",
+        "picked_transform_watcher"
+      ]
+    }
+  ]
+}

+ 3 - 58
tests/interface/ndi.cpp

@@ -1,78 +1,23 @@
 #define BOOST_TEST_DYN_LINK
 #define BOOST_TEST_MAIN  // in only one cpp file
 
-#include "utility/variable_helper.hpp"
-#include "core/basic_obj_types.hpp"
+#include "core/global_defs.h"
 
-#include <boost/asio/co_spawn.hpp>
-#include <boost/asio/detached.hpp>
-#include <boost/asio/this_coro.hpp>
-#include <boost/asio/use_awaitable.hpp>
 #include <boost/test/unit_test.hpp>
 
 #include <spdlog/spdlog.h>
 
-#include <chrono>
 #include <fstream>
-#include <iostream>
-#include <vector>
-
-using boost::asio::awaitable;
-using boost::asio::co_spawn;
-using boost::asio::detached;
-using boost::asio::use_awaitable;
 
 using namespace sophiar;
 using namespace std::chrono_literals;
 
-//awaitable<void> coro_ndi_test() {
-//    auto interface = std::make_unique<ndi_interface>();
-//    auto init_config = nlohmann::json::parse(
-//            R"({"address_type":"ethernet","ip":"169.254.132.51","tcp_port":8765,"com_port":"COM3","tool_list":[{"rom_path":"D:\\Program\\Robot\\Tools\\roms\\Probe_Small_4Ball.rom","outputs":{"transform":"tracker_probe_transform","marker_uncertainty":"tracker_probe_transform_uncertainty"}},{"rom_path":"D:\\Program\\Robot\\Tools\\roms\\Head_3Ball_2.rom","outputs":{"transform":"tracker_model_ref_transform","marker_uncertainty":"tracker_model_ref_transform_uncertainty"}}]})");
-//    auto start_config = nlohmann::json::parse(
-//            R"({"allow_unreliable":true,"prefer_stream_tracking":true})");
-//
-//    BOOST_TEST(co_await interface->init(init_config));
-//    BOOST_TEST(co_await interface->start(start_config));
-//    auto trans_obj = global_obj_auto_sync_delegate<transform_obj>(
-//            global_sophiar_manager,
-//            "tracker_probe_transform");
-//    int cnt = 0;
-//    FILE_LINE_TRACE
-//    for (;;) {
-//        co_await trans_obj.coro_wait_update();
-////        if (!trans_obj.empty()) {
-////            std::cout << trans_obj->value.matrix() << std::endl;
-////        } else {
-////            std::cout << "empty" << std::endl;
-////        }
-//        if (++cnt == 250) break;
-//    }
-//    FILE_LINE_TRACE
-//    co_await interface->reset();
-//
-//    start_config = nlohmann::json::parse(
-//            R"({"allow_unreliable":true,"prefer_stream_tracking":false})");
-//    BOOST_TEST(co_await interface->init(init_config));
-//    BOOST_TEST(co_await interface->start(start_config));
-//    cnt = 0;
-//    FILE_LINE_TRACE
-//    for (;;) {
-//        co_await trans_obj.coro_wait_update();
-//        if (++cnt == 60) break;
-//    }
-//    FILE_LINE_TRACE
-//    co_await interface->reset();
-//
-//    co_return;
-//}
-
 BOOST_AUTO_TEST_CASE(test_ndi) {
     spdlog::set_level(spdlog::level::trace);
     std::ifstream config_file("data/ndi_interface_config.json");
-    assert(config_file.is_open());
+    BOOST_TEST(config_file.is_open());
     auto config = nlohmann::json::parse(config_file);
     auto ok = initialize(config);
-    assert(ok);
+    BOOST_TEST(ok);
     global_context->run();
 }

+ 22 - 0
tests/interface/ndi_stabilizer.cpp

@@ -0,0 +1,22 @@
+#define BOOST_TEST_DYN_LINK
+
+#include "core/global_defs.h"
+
+#include <boost/test/unit_test.hpp>
+
+#include <spdlog/spdlog.h>
+
+#include <fstream>
+
+using namespace sophiar;
+using namespace std::chrono_literals;
+
+BOOST_AUTO_TEST_CASE(test_ndi_stabilizer) {
+    spdlog::set_level(spdlog::level::trace);
+    std::ifstream config_file("data/ndi_stabilizer_config.json");
+    BOOST_TEST(config_file.is_open());
+    auto config = nlohmann::json::parse(config_file);
+    auto ok = initialize(config);
+    BOOST_TEST(ok);
+    global_context->run();
+}