@@ -37,9 +37,10 @@ namespace yolox_ros_cpp
3737 {
3838#ifdef ENABLE_TENSORRT
3939 RCLCPP_INFO (this ->get_logger (), " Model Type is TensorRT" );
40- this ->yolox_ = std::make_unique<yolox_cpp::YoloXTensorRT>(this ->params_ .model_path , this ->params_ .tensorrt_device ,
41- this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
42- this ->params_ .num_classes , this ->params_ .p6 );
40+ this ->yolox_ = std::make_unique<yolox_cpp::YoloXTensorRT>(
41+ this ->params_ .model_path , this ->params_ .tensorrt_device ,
42+ this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
43+ this ->params_ .num_classes , this ->params_ .p6 );
4344#else
4445 RCLCPP_ERROR (this ->get_logger (), " yolox_cpp is not built with TensorRT" );
4546 rclcpp::shutdown ();
@@ -49,9 +50,10 @@ namespace yolox_ros_cpp
4950 {
5051#ifdef ENABLE_OPENVINO
5152 RCLCPP_INFO (this ->get_logger (), " Model Type is OpenVINO" );
52- this ->yolox_ = std::make_unique<yolox_cpp::YoloXOpenVINO>(this ->params_ .model_path , this ->params_ .openvino_device ,
53- this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
54- this ->params_ .num_classes , this ->params_ .p6 );
53+ this ->yolox_ = std::make_unique<yolox_cpp::YoloXOpenVINO>(
54+ this ->params_ .model_path , this ->params_ .openvino_device ,
55+ this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
56+ this ->params_ .num_classes , this ->params_ .p6 );
5557#else
5658 RCLCPP_ERROR (this ->get_logger (), " yolox_cpp is not built with OpenVINO" );
5759 rclcpp::shutdown ();
@@ -61,13 +63,14 @@ namespace yolox_ros_cpp
6163 {
6264#ifdef ENABLE_ONNXRUNTIME
6365 RCLCPP_INFO (this ->get_logger (), " Model Type is ONNXRuntime" );
64- this ->yolox_ = std::make_unique<yolox_cpp::YoloXONNXRuntime>(this ->params_ .model_path ,
65- this ->params_ .onnxruntime_intra_op_num_threads_ ,
66- this ->params_ .onnxruntime_inter_op_num_threads_ ,
67- this ->params_ .onnxruntime_use_cuda_ , this ->params_ .onnxruntime_device_id ,
68- this ->params_ .onnxruntime_use_parallel ,
69- this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
70- this ->params_ .num_classes , this ->params_ .p6 );
66+ this ->yolox_ = std::make_unique<yolox_cpp::YoloXONNXRuntime>(
67+ this ->params_ .model_path ,
68+ this ->params_ .onnxruntime_intra_op_num_threads_ ,
69+ this ->params_ .onnxruntime_inter_op_num_threads_ ,
70+ this ->params_ .onnxruntime_use_cuda_ , this ->params_ .onnxruntime_device_id ,
71+ this ->params_ .onnxruntime_use_parallel ,
72+ this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
73+ this ->params_ .num_classes , this ->params_ .p6 );
7174#else
7275 RCLCPP_ERROR (this ->get_logger (), " yolox_cpp is not built with ONNXRuntime" );
7376 rclcpp::shutdown ();
@@ -77,9 +80,10 @@ namespace yolox_ros_cpp
7780 {
7881#ifdef ENABLE_TFLITE
7982 RCLCPP_INFO (this ->get_logger (), " Model Type is tflite" );
80- this ->yolox_ = std::make_unique<yolox_cpp::YoloXTflite>(this ->params_ .model_path , this ->params_ .tflite_num_threads_ ,
81- this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
82- this ->params_ .num_classes , this ->params_ .p6 , this ->params_ .is_nchw );
83+ this ->yolox_ = std::make_unique<yolox_cpp::YoloXTflite>(
84+ this ->params_ .model_path , this ->params_ .tflite_num_threads_ ,
85+ this ->params_ .nms , this ->params_ .conf , this ->params_ .model_version ,
86+ this ->params_ .num_classes , this ->params_ .p6 , this ->params_ .is_nchw );
8387#else
8488 RCLCPP_ERROR (this ->get_logger (), " yolox_cpp is not built with tflite" );
8589 rclcpp::shutdown ();
0 commit comments