Skip to content

Commit fc3a9e0

Browse files
Aligned implementation with SAM updated model (using agrs for initializing)
1 parent 90605c0 commit fc3a9e0

File tree

2 files changed

+8
-5
lines changed

2 files changed

+8
-5
lines changed

ed_sensor_integration/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ find_package(catkin REQUIRED COMPONENTS
4747
tue_filesystem
4848
visualization_msgs
4949
# 2D -> 3D point cloud estimation
50-
# onnxruntime_ros
50+
onnxruntime_ros
5151
yolo_onnx_ros
5252
sam_onnx_ros
5353
bmm_ros

ed_sensor_integration/src/kinect/sam_seg_module.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -16,17 +16,20 @@ std::vector<cv::Mat> SegmentationPipeline(const cv::Mat& img, tue::Configuration
1616
////////////////////////// YOLO //////////////////////////////////////
1717
std::unique_ptr<YOLO_V8> yoloDetector;
1818
DL_INIT_PARAM params;
19-
std::string model;
20-
config.value("model", model);
21-
std::tie(yoloDetector, params) = Initialize(model);
19+
std::string yolo_model, sam_encoder, sam_decoder;
20+
config.value("yolo_model", yolo_model);
21+
config.value("sam_encoder", sam_encoder);
22+
config.value("sam_decoder", sam_decoder);
23+
24+
std::tie(yoloDetector, params) = Initialize(yolo_model);
2225
////////////////////////// SAM //////////////////////////////////////
2326

2427
std::vector<std::unique_ptr<SAM>> samSegmentors;
2528
SEG::DL_INIT_PARAM params_encoder;
2629
SEG::DL_INIT_PARAM params_decoder;
2730
std::vector<SEG::DL_RESULT> resSam;
2831
SEG::DL_RESULT res;
29-
std::tie(samSegmentors, params_encoder, params_decoder, res, resSam) = Initializer();
32+
std::tie(samSegmentors, params_encoder, params_decoder, res, resSam) = Initialize(sam_encoder, sam_decoder);
3033

3134

3235
////////////////////////// YOLO //////////////////////////////////////

0 commit comments

Comments
 (0)