Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 5 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@ add_compile_options(-Wextra -Werror=extra)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)


find_package(OpenCV REQUIRED)
find_package(catkin REQUIRED
COMPONENTS
onnxruntime_ros
)

find_package(console_bridge REQUIRED)
find_package(OpenCV REQUIRED)

set(${PROJECT_NAME}_CUDA_ENABLED ${onnxruntime_ros_CUDA_ENABLED})
if(${PROJECT_NAME}_CUDA_ENABLED)
Expand All @@ -35,7 +35,7 @@ catkin_package(
INCLUDE_DIRS include ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS onnxruntime_ros
DEPENDS ${${PROJECT_NAME}_CUDA_CATKIN_DEPENDS} OpenCV
DEPENDS ${${PROJECT_NAME}_CUDA_CATKIN_DEPENDS} OpenCV console_bridge
)

# ------------------------------------------------------------------------------------------------
Expand All @@ -47,6 +47,7 @@ include_directories(
${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}
SYSTEM
${${PROJECT_NAME}_CUDA_INCLUDE_DIRS}
${console_bridge_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
Expand All @@ -55,7 +56,7 @@ add_library(${PROJECT_NAME}
src/detection.cpp
src/yolo_inference.cpp
)
target_link_libraries(${PROJECT_NAME} ${${PROJECT_NAME}_CUDA_TARGET_LINK_LIBRARIES} ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})
target_link_libraries(${PROJECT_NAME} ${${PROJECT_NAME}_CUDA_TARGET_LINK_LIBRARIES} ${console_bridge_LIBRARIES} ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})
# add_dependencies(${PROJECT_NAME} generate_config_hpp)

add_executable(test_${PROJECT_NAME}
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>libconsole-bridge-dev</depend>
<depend>onnxruntime_ros</depend>

<build_depend>libopencv-dev</build_depend>
Expand Down
10 changes: 6 additions & 4 deletions src/detection.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include "yolo_onnx_ros/detection.hpp"
#include <yolo_onnx_ros/config.hpp>

#include <console_bridge/console.h>

#include <fstream>
#include <iomanip>
#include <iostream>
Expand Down Expand Up @@ -94,7 +96,7 @@ int ReadYaml(const std::filesystem::path& filename, std::unique_ptr<YOLO_V8>& p)
std::ifstream file(filename);
if (!file.is_open())
{
std::cerr << "[ReadYaml] Failed to open: " << filename << std::endl;
CONSOLE_BRIDGE_logError("[ReadYaml] Failed to open: %s", filename.c_str());
return 1;
}

Expand Down Expand Up @@ -128,7 +130,7 @@ int ReadYaml(const std::filesystem::path& filename, std::unique_ptr<YOLO_V8>& p)

if (!in_names_section || start >= lines.size())
{
std::cerr << "[ReadYaml] Could not find 'names:' section in " << filename << std::endl;
CONSOLE_BRIDGE_logError("[ReadYaml] Could not find 'names:' section in %s", filename.c_str());
return 1;
}

Expand Down Expand Up @@ -166,12 +168,12 @@ int ReadYaml(const std::filesystem::path& filename, std::unique_ptr<YOLO_V8>& p)

if (names.empty())
{
std::cerr << "[ReadYaml] No class names found in " << filename << std::endl;
CONSOLE_BRIDGE_logError("[ReadYaml] No class names found in %s", filename.c_str());
return 1;
}

p->classes = names;
std::cout << "[ReadYaml] Loaded " << names.size() << " classes from " << filename << std::endl;
CONSOLE_BRIDGE_logInform("[ReadYaml] Loaded %u classes from %s", names.size(), filename.c_str());
return 0;
}

Expand Down
8 changes: 3 additions & 5 deletions src/main.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
#include <iostream>
#include <iomanip>
#include "yolo_onnx_ros/detection.hpp"

#include <filesystem>
#include <fstream>
#include <random>
#include <iostream>

int main(int argc, char *argv[])
{
Expand All @@ -21,7 +19,7 @@ int main(int argc, char *argv[])
std::tie(yoloDetector, params) = Initialize(model_name);

std::filesystem::path imgs_path = argv[2];
for (auto& i : std::filesystem::directory_iterator(imgs_path))
for (const auto& i : std::filesystem::directory_iterator(imgs_path))
{
if (i.path().extension() == ".jpg" || i.path().extension() == ".png" || i.path().extension() == ".jpeg")
{
Expand Down
32 changes: 17 additions & 15 deletions src/yolo_inference.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
#include "yolo_onnx_ros/yolo_inference.hpp"

#include <console_bridge/console.h>

#include <regex>
#include <sstream>

#define benchmark
#define min(a, b) (((a) < (b)) ? (a) : (b))
Expand Down Expand Up @@ -118,8 +122,7 @@ const char* YOLO_V8::CreateSession(DL_INIT_PARAM& iParams) {
bool result = std::regex_search(iParams.modelPath, pattern);
if (result)
{
Ret = "[YOLO_V8]:Your model path is error. Change your model path without chinese characters.";
std::cout << Ret << std::endl;
CONSOLE_BRIDGE_logInform("[YOLO_V8]:Your model path is error. Change your model path without chinese characters.");
return Ret;
}
try
Expand Down Expand Up @@ -166,14 +169,9 @@ const char* YOLO_V8::CreateSession(DL_INIT_PARAM& iParams) {
}
catch (const std::exception& e)
{
const char* str1 = "[YOLO_V8]:";
const char* str2 = e.what();
std::string result = std::string(str1) + std::string(str2);
char* merged = new char[result.length() + 1];
std::strcpy(merged, result.c_str());
std::cout << merged << std::endl;
delete[] merged;
return "[YOLO_V8]:Create session failed.";
std::string error_msg = "[YOLO_V8]: Failed to create session: " + std::string(e.what());
CONSOLE_BRIDGE_logError(error_msg.c_str());
throw std::runtime_error(error_msg);
}

}
Expand Down Expand Up @@ -301,14 +299,18 @@ char* YOLO_V8::TensorProcess(clock_t& starttime_1, N& blob, std::vector<int64_t>
double pre_process_time = (double)(starttime_2 - starttime_1) / CLOCKS_PER_SEC * 1000;
double process_time = (double)(starttime_3 - starttime_2) / CLOCKS_PER_SEC * 1000;
double post_process_time = (double)(starttime_4 - starttime_3) / CLOCKS_PER_SEC * 1000;
std::stringstream ss;
if (cudaEnable_)
{
std::cout << "[YOLO_V8(CUDA)]: " << pre_process_time << "ms pre-process, " << process_time << "ms inference, " << post_process_time << "ms post-process." << std::endl;

ss << "[YOLO_V8(CUDA)]: ";
}
else
{
std::cout << "[YOLO_V8(CPU)]: " << pre_process_time << "ms pre-process, " << process_time << "ms inference, " << post_process_time << "ms post-process." << std::endl;
ss << "[YOLO_V8(CPU)]: ";
}
ss << pre_process_time << "ms pre-process, " << process_time << "ms inference, " << post_process_time << "ms post-process." << std::endl;
CONSOLE_BRIDGE_logInform(ss.str().c_str());
#endif // benchmark

break;
Expand Down Expand Up @@ -337,7 +339,7 @@ char* YOLO_V8::TensorProcess(clock_t& starttime_1, N& blob, std::vector<int64_t>
break;
}
default:
std::cout << "[YOLO_V8]: " << "Not support model type." << std::endl;
CONSOLE_BRIDGE_logError("[YOLO_V8]: Not support model type.");
}
return RET_OK;

Expand Down Expand Up @@ -365,7 +367,7 @@ char* YOLO_V8::WarmUpSession() {
double post_process_time = (double)(starttime_4 - starttime_1) / CLOCKS_PER_SEC * 1000;
if (cudaEnable_)
{
std::cout << "[YOLO_V8(CUDA)]: " << "Cuda warm-up cost " << post_process_time << " ms. " << std::endl;
CONSOLE_BRIDGE_logInform("[YOLO_V8(CUDA)]: CUDA warm-up cost %f ms.", post_process_time);
}
}
else
Expand All @@ -381,7 +383,7 @@ char* YOLO_V8::WarmUpSession() {
double post_process_time = (double)(starttime_4 - starttime_1) / CLOCKS_PER_SEC * 1000;
if (cudaEnable_)
{
std::cout << "[YOLO_V8(CUDA)]: " << "Cuda warm-up cost " << post_process_time << " ms. " << std::endl;
CONSOLE_BRIDGE_logInform("[YOLO_V8(CUDA)]: CUDA warm-up cost %f ms.", post_process_time);
}
#endif
}
Expand Down
4 changes: 2 additions & 2 deletions test/yolo_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,8 @@ TEST_F(YoloInferenceTest, CreateSessionWithValidModel)
TEST_F(YoloInferenceTest, CreateSessionWithInvalidModel)
{
params.modelPath = "nonexistent_model.onnx";
const char* result = yolo->CreateSession(params);
EXPECT_NE(result, nullptr) << "CreateSession should fail with invalid model path";
EXPECT_THROW(yolo->CreateSession(params), std::runtime_error)
<< "CreateSession should throw an exception with invalid model path";
}

TEST_F(YoloInferenceTest, FullInferencePipeline)
Expand Down