浏览代码

Make windows happy.

jcsyshc 2 年之前
父节点
当前提交
ac0fa7277f
共有 6 个文件被更改,包括 77 次插入59 次删除
  1. 8 1
      CMakeLists.txt
  2. 3 3
      data/config.yaml
  3. 4 4
      data/sophiar_config.json
  4. 9 5
      src/image_process/process_kernels.cu
  5. 52 45
      src/main_ext.cpp
  6. 1 1
      src/utility.hpp

+ 8 - 1
CMakeLists.txt

@@ -104,6 +104,9 @@ target_sources(${PROJECT_NAME} PRIVATE src/video_encoder.cpp)
 find_package(yaml-cpp REQUIRED)
 target_include_directories(${PROJECT_NAME} PRIVATE ${YAML_CPP_INCLUDE_DIR})
 target_link_libraries(${PROJECT_NAME} ${YAML_CPP_LIBRARIES})
+if (WIN32)
+    target_link_directories(${PROJECT_NAME} PRIVATE C:/BuildEssentials/VS2019Libs/lib)
+endif ()
 
 # Boost config
 find_package(Boost REQUIRED COMPONENTS iostreams)
@@ -125,7 +128,11 @@ find_package(nlohmann_json REQUIRED)
 target_link_libraries(${PROJECT_NAME} nlohmann_json::nlohmann_json)
 
 # Sophiar2 config
-set(Sophiar2DIR /home/tpx/project/Sophiar2)
+if (WIN32)
+    set(Sophiar2DIR D:/Program/Robot/Sophiar2)
+else ()
+    set(Sophiar2DIR /home/tpx/project/Sophiar2)
+endif ()
 add_subdirectory(${Sophiar2DIR}/src Sophiar2Lib)
 target_include_directories(${PROJECT_NAME} PRIVATE ${Sophiar2DIR}/src)
 target_link_libraries(${PROJECT_NAME} Sophiar2Lib)

+ 3 - 3
data/config.yaml

@@ -44,11 +44,11 @@ sophiar:
   config: ./sophiar_config.json
   left_camera_trans_var: left_camera_in_tracker_denoised
   right_camera_trans_var: right_camera_in_tracker_denoised
-  probe_model: /home/tpx/data/stls/Probe.stl
+  probe_model: ./models/Probe.stl
   augment:
     - name: Femur
       trans_var: femur_in_tracker_denoised
-      stl_file: /home/tpx/project/RemoteAR3/data/femur.stl
+      stl_file: ./models/femur.stl
       registration:
         collect_obj: point_picker_in_femur_ref
         collect_var: picked_point_in_femur_ref
@@ -56,7 +56,7 @@ sophiar:
         probe_var: probe_in_femur
     - name: Tibia
       trans_var: tibia_in_tracker_denoised
-      stl_file: /home/tpx/project/RemoteAR3/data/tibia.stl
+      stl_file: ./models/tibia.stl
       registration:
         collect_obj: point_picker_in_tibia_ref
         collect_var: picked_point_in_tibia_ref

+ 4 - 4
data/sophiar_config.json

@@ -266,25 +266,25 @@
         "com_port": "/dev/ttyUSB0",
         "tool_list": [
           {
-            "rom_path": "/home/tpx/data/roms/GlassProbe_4Ball_4.rom",
+            "rom_path": "./roms/GlassProbe_4Ball_4.rom",
             "outputs": {
               "transform": "probe_in_tracker"
             }
           },
           {
-            "rom_path": "/home/tpx/data/roms/Glass_4Ball_1.rom",
+            "rom_path": "./roms/Glass_4Ball_1.rom",
             "outputs": {
               "transform": "camera_ref_in_tracker"
             }
           },
           {
-            "rom_path": "/home/tpx/data/roms/Glass_3Ball_6.rom",
+            "rom_path": "./roms/Glass_3Ball_6.rom",
             "outputs": {
               "transform": "femur_ref_in_tracker"
             }
           },
           {
-            "rom_path": "/home/tpx/data/roms/Glass_3Ball_5.rom",
+            "rom_path": "./roms/Glass_3Ball_5.rom",
             "outputs": {
               "transform": "tibia_ref_in_tracker"
             }

+ 9 - 5
src/image_process/process_kernels.cu

@@ -396,13 +396,15 @@ __global__ void crude_debayer(image_type<InT> in, image_type<OutT> out) {
     for (uint32_t iy = get_iy(); iy < out.height; iy += gh)
         for (uint32_t ix = get_ix(); ix < out.width; ix += gw) {
             // fetch elements
-            using FetchType = packed_type<InT, 2>::type;
+            using FetchType = typename packed_type<InT, 2>::type;
             auto raw_rg = image_fetch<InT, FetchType>(in, ix, iy << 1);
             auto raw_gb = image_fetch<InT, FetchType>(in, ix, (iy << 1) | 1);
 
             // reconstruct
-            static_assert(std::is_integral_v<InT>);
-            static_assert(sizeof(InT) < sizeof(uint32_t));
+            static_assert(std::is_integral_v<InT>,
+                          "Type of image element must be one channel integer.");
+            static_assert(sizeof(InT) < sizeof(uint32_t),
+                          "Size of image element must be smaller than int.");
             InT r = raw_rg.x;
             InT g = ((uint32_t) raw_rg.y + (uint32_t) raw_gb.x) >> 1;
             InT b = raw_gb.y;
@@ -441,8 +443,10 @@ __global__ void resample_image(cudaTextureObject_t in, image_type<ImgT> out,
             auto val = tex2D<float4>(in, u, v);
             ImgT ret;
             using ElemT = decltype(ret.x);
-            static_assert(std::is_integral_v<ElemT>);
-            static_assert(std::is_same_v<ImgT, typename packed_type<ElemT, 3>::type>);
+            static_assert(std::is_integral_v<ElemT>,
+                          "Type of output image element must be integer.");
+            static_assert(std::is_same_v<ImgT, typename packed_type<ElemT, 3>::type>,
+                          "Type of output image element must have three channels.");
             constexpr auto factor = type_max_value<ElemT>::value;
             ret.x = factor * val.x;
             ret.y = factor * val.y;

+ 52 - 45
src/main_ext.cpp

@@ -13,6 +13,14 @@
 #include "video_encoder.h"
 #include "vtk_viewer.h"
 
+#ifdef _MSC_VER
+
+#include <format>
+
+#define fmt std
+
+#endif
+
 #include <spdlog/spdlog.h>
 
 #include <yaml-cpp/yaml.h>
@@ -35,6 +43,7 @@
 
 #include <cassert>
 #include <functional>
+#include <numbers>
 #include <thread>
 #include <queue>
 #include <vector>
@@ -110,12 +119,16 @@ struct camera_related {
     std::string trans_var;
     image_process_config process_conf;
 
-    // remap related
-//    std::string remap_data_path;
-//    std::unique_ptr<smart_texture> remap_tex;
     bool augment_available = false;
     std::unique_ptr<smart_texture> augment_tex;
 
+    camera_related() {
+        img_dev = std::make_unique<cv::cuda::GpuMat>();
+        stream = std::make_unique<cv::cuda::Stream>();
+        cuda_stream = (cudaStream_t) stream->cudaPtr();
+        processor = std::make_unique<monocular_processor>();
+    }
+
     void load_intrinsic(YAML::Node conf) {
         camera_intrinsic info;
         info.fx = conf["fx"].as<float>();
@@ -183,7 +196,7 @@ struct camera_related {
     }
 };
 
-camera_related left, right;
+std::unique_ptr<camera_related> left, right;
 
 constexpr auto config_path = "./config.yaml";
 
@@ -209,14 +222,8 @@ void initialize_cuda() {
     });
 
     // create some cuda objects
-    left.img_dev = std::make_unique<cv::cuda::GpuMat>();
-    right.img_dev = std::make_unique<cv::cuda::GpuMat>();
-    left.stream = std::make_unique<cv::cuda::Stream>();
-    right.stream = std::make_unique<cv::cuda::Stream>();
-    left.cuda_stream = (cudaStream_t) left.stream->cudaPtr();
-    right.cuda_stream = (cudaStream_t) right.stream->cudaPtr();
-    left.processor = std::make_unique<monocular_processor>();
-    right.processor = std::make_unique<monocular_processor>();
+    left = std::make_unique<camera_related>();
+    right = std::make_unique<camera_related>();
     output_stream = std::make_unique<cv::cuda::Stream>();
     output_cuda_stream = (cudaStream_t) output_stream->cudaPtr();
     output_frame_dev = std::make_shared<cv::cuda::GpuMat>();
@@ -238,16 +245,16 @@ void load_config() {
 
     // load camera intrinsics
     auto intrinsic_conf = camera_conf["intrinsic"];
-    left.load_intrinsic(intrinsic_conf["left"]);
-    right.load_intrinsic(intrinsic_conf["right"]);
+    left->load_intrinsic(intrinsic_conf["left"]);
+    right->load_intrinsic(intrinsic_conf["right"]);
 
     // calculate valid resample range
-    auto range = calc_valid_range(left.process_conf.camera,
-                                  right.process_conf.camera,
+    auto range = calc_valid_range(left->process_conf.camera,
+                                  right->process_conf.camera,
                                   &augment_render_angle);
     augment_render_angle *= 180 / std::numbers::pi;
-    left.process_conf.valid_range = range;
-    right.process_conf.valid_range = range;
+    left->process_conf.valid_range = range;
+    right->process_conf.valid_range = range;
 
     // load main window config
     auto window_conf = conf["main_window"];
@@ -259,8 +266,8 @@ void load_config() {
     output_width = output_conf["width"].as<int>();
     output_height = output_conf["height"].as<int>();
     main_encoder_conf.bitrate_mbps = output_conf["bitrate"].as<float>();
-    left.process_conf.resample_height = output_height; // use output height as resample height
-    right.process_conf.resample_height = output_height;
+    left->process_conf.resample_height = output_height; // use output height as resample height
+    right->process_conf.resample_height = output_height;
 
     // load sender config
     auto sender_conf = conf["sender"];
@@ -271,8 +278,8 @@ void load_config() {
     // load sophiar config
     auto sophiar_conf = conf["sophiar"];
     sophiar_config_path = sophiar_conf["config"].as<std::string>();
-    left.trans_var = sophiar_conf["left_camera_trans_var"].as<std::string>();
-    right.trans_var = sophiar_conf["right_camera_trans_var"].as<std::string>();
+    left->trans_var = sophiar_conf["left_camera_trans_var"].as<std::string>();
+    right->trans_var = sophiar_conf["right_camera_trans_var"].as<std::string>();
     probe_model_path = sophiar_conf["probe_model"].as<std::string>();
 
     // load augment items
@@ -349,8 +356,8 @@ void initialize_main_window() {
     // initialize OpenGL objects
     opengl_render = std::make_unique<simple_render>();
     output_fbo = std::make_unique<smart_frame_buffer>();
-    left.augment_tex = std::make_unique<smart_texture>();
-    right.augment_tex = std::make_unique<smart_texture>();
+    left->augment_tex = std::make_unique<smart_texture>();
+    right->augment_tex = std::make_unique<smart_texture>();
 
     // elegant cleanup
     std::atexit([] {
@@ -384,9 +391,9 @@ void initialize_main_window() {
     vtk_test1 = std::make_unique<vtk_viewer>();
     vtk_test2 = std::make_unique<vtk_viewer>();
     vtk_test1->clear_actor();
-    vtk_test1->add_actor(create_actor("/home/tpx/data/stls/GlassProbe_4Ball_3.STL"));
+    vtk_test1->add_actor(create_actor("./models/femur.stl"));
     vtk_test1->reset_camera();
-    vtk_test2->add_actor(create_actor("/home/tpx/data/stls/HeadModelDrill.stl"));
+    vtk_test2->add_actor(create_actor("./models/tibia.stl"));
     vtk_test1->start_picking();
 }
 
@@ -538,11 +545,11 @@ void upload_encoder_config() {
 
 void start_encoder() {
     if (output_full_frame) {
-        assert(!left.img_dev->empty() && !right.img_dev->empty());
-        assert(left.img_dev->size() == right.img_dev->size());
+        assert(!left->img_dev->empty() && !right->img_dev->empty());
+        assert(left->img_dev->size() == right->img_dev->size());
         main_encoder_conf.frame_size = cv::Size{
-                left.img_dev->size().width * 2,
-                left.img_dev->size().height};
+                left->img_dev->size().width * 2,
+                left->img_dev->size().height};
         output_fbo->create(main_encoder_conf.frame_size);
     } else {
         main_encoder_conf.frame_size = cv::Size{output_width, output_height};
@@ -575,8 +582,8 @@ void cleanup() {
     // avoid cudaErrorCudartUnloading
     opengl_render.reset();
     output_fbo.reset();
-    left.processor.reset();
-    right.processor.reset();
+    left.reset();
+    right.reset();
 
     // stop sophiar
     assert(sophiar_thread != nullptr);
@@ -866,8 +873,8 @@ void handle_imgui_events() {
 
 void wait_camera_frames() {
     assert(is_capturing());
-    left.wait_frame(IMG_RAW_HOST_LEFT);
-    right.wait_frame(IMG_RAW_HOST_RIGHT);
+    left->wait_frame(IMG_RAW_HOST_LEFT);
+    right->wait_frame(IMG_RAW_HOST_RIGHT);
 }
 
 void process_camera_frames() {
@@ -877,8 +884,8 @@ void process_camera_frames() {
         update_actor_pose(item.actor, trans);
     }
 
-    left.process_frame(IMG_RAW_HOST_LEFT);
-    right.process_frame(IMG_RAW_HOST_RIGHT);
+    left->process_frame(IMG_RAW_HOST_LEFT);
+    right->process_frame(IMG_RAW_HOST_RIGHT);
 }
 
 void render_main_window() {
@@ -890,19 +897,19 @@ void render_main_window() {
 
     if (is_capturing()) {
         // draw preview camera frame
-        assert(left.img_dev->size() == right.img_dev->size());
-        float width_normal = left.img_dev->size().aspectRatio() / frame_size.aspectRatio();
+        assert(left->img_dev->size() == right.img_dev->size());
+        float width_normal = left->img_dev->size().aspectRatio() / frame_size.aspectRatio();
         auto render_rect = simple_rect{
                 -width_normal, -1, 2 * width_normal, 2
         };
         if (preview_camera_index == 0) { // left camera
-            if (!left.img_dev->empty()) {
-                left.render(render_rect);
+            if (!left->img_dev->empty()) {
+                left->render(render_rect);
             }
         } else { // right camera
             assert(preview_camera_index == 1);
-            if (!right.img_dev->empty()) {
-                right.render(render_rect);
+            if (!right->img_dev->empty()) {
+                right->render(render_rect);
             }
         }
     }
@@ -926,13 +933,13 @@ void generate_output_frame() {
         left_rect = simple_rect{-1, -1, 1, 2};
         right_rect = simple_rect{0, -1, 1, 2};
     } else {
-        float width_normal = left.img_dev->size().aspectRatio() /
+        float width_normal = left->img_dev->size().aspectRatio() /
                              output_fbo->size().aspectRatio();
         left_rect = simple_rect{-0.5f - width_normal / 2, -1, width_normal, 2};
         right_rect = simple_rect{0.5f - width_normal / 2, -1, width_normal, 2};
     }
-    left.render(left_rect, true);
-    right.render(right_rect, true);
+    left->render(left_rect, true);
+    right->render(right_rect, true);
 
     // wait encoder idle
     for (uint64_t cur_cnt = 0;;) {

+ 1 - 1
src/utility.hpp

@@ -15,7 +15,7 @@ inline bool check_function_call(bool function_ret, unsigned int line_number,
     if (function_ret) [[likely]] return true;
     SPDLOG_ERROR("Function call {} failed at {}:{}.",
                  function_call_str, file_name, line_number);
-    RET_ERROR;
+    RET_ERROR_B;
 }
 
 #define CALL_CHECK(function_call) \