• detect_topic


    1.接收ros图像

    2.yolo识别

    3.sort跟踪

     yolo.h

    1. #ifndef YOLO_H
    2. #define YOLO_H
    3. #include <cuda_runtime_api.h>
    4. #include <opencv2/opencv.hpp>
    5. #include "NvInfer.h"
    6. #include "NvInferPlugin.h"
    7. #include "NvInferRuntimeCommon.h"
    8. #include "NvOnnxParser.h"
    9. #include <math.h>
    10. #include <array>
    11. #include <fstream>
    12. #include <iostream>
    13. #include <random>
    14. #include <sstream>
    15. #include <string>
    16. #include <vector>
    17. using nvinfer1::Dims2;
    18. using nvinfer1::Dims3;
    19. using nvinfer1::IBuilder;
    20. using nvinfer1::IBuilderConfig;
    21. using nvinfer1::ICudaEngine;
    22. using nvinfer1::IExecutionContext;
    23. using nvinfer1::IHostMemory;
    24. using nvinfer1::ILogger;
    25. using nvinfer1::INetworkDefinition;
    26. using Severity = nvinfer1::ILogger::Severity;
    27. using cv::Mat;
    28. using std::array;
    29. using std::cout;
    30. using std::endl;
    31. using std::ifstream;
    32. using std::ios;
    33. using std::ofstream;
    34. using std::string;
    35. using std::vector;
    36. class Logger : public ILogger {
    37. public:
    38. void log(Severity severity, const char* msg) noexcept override {
    39. if (severity != Severity::kINFO) {
    40. std::cout << msg << std::endl;
    41. }
    42. }
    43. };
    44. class Yolo {
    45. public:
    46. Yolo(char* model_path);
    47. float letterbox(
    48. const cv::Mat& image,
    49. cv::Mat& out_image,
    50. const cv::Size& new_shape,
    51. int stride,
    52. const cv::Scalar& color,
    53. bool fixed_shape,
    54. bool scale_up);
    55. float* blobFromImage(cv::Mat& img);
    56. void draw_objects(const cv::Mat& img, float* Boxes, int* ClassIndexs, int* BboxNum, float* Scores);
    57. void Init(char* model_path);
    58. void Infer(
    59. int aWidth,
    60. int aHeight,
    61. int aChannel,
    62. unsigned char* aBytes,
    63. float* Boxes,
    64. int* ClassIndexs,
    65. int* BboxNum,
    66. float* Scores);
    67. ~Yolo();
    68. private:
    69. nvinfer1::ICudaEngine* engine = nullptr;
    70. nvinfer1::IRuntime* runtime = nullptr;
    71. nvinfer1::IExecutionContext* context = nullptr;
    72. cudaStream_t stream = nullptr;
    73. void* buffs[5];
    74. int iH, iW, in_size, out_size1, out_size2, out_size3, out_size4;
    75. Logger gLogger;
    76. };
    77. #endif // YOLO_H

    yolo.cpp

    1. #include "yolo.h"
    2. float Yolo::letterbox(
    3. const cv::Mat& image,
    4. cv::Mat& out_image,
    5. const cv::Size& new_shape = cv::Size(640, 640),
    6. int stride = 32,
    7. const cv::Scalar& color = cv::Scalar(114, 114, 114),
    8. bool fixed_shape = false,
    9. bool scale_up = true) {
    10. cv::Size shape = image.size();
    11. float r = std::min(
    12. (float)new_shape.height / (float)shape.height, (float)new_shape.width / (float)shape.width);
    13. if (!scale_up) {
    14. r = std::min(r, 1.0f);
    15. }
    16. int newUnpad[2]{
    17. (int)std::round((float)shape.width * r), (int)std::round((float)shape.height * r)};
    18. cv::Mat tmp;
    19. if (shape.width != newUnpad[0] || shape.height != newUnpad[1]) {
    20. cv::resize(image, tmp, cv::Size(newUnpad[0], newUnpad[1]));
    21. } else {
    22. tmp = image.clone();
    23. }
    24. float dw = new_shape.width - newUnpad[0];
    25. float dh = new_shape.height - newUnpad[1];
    26. if (!fixed_shape) {
    27. dw = (float)((int)dw % stride);
    28. dh = (float)((int)dh % stride);
    29. }
    30. dw /= 2.0f;
    31. dh /= 2.0f;
    32. int top = int(std::round(dh - 0.1f));
    33. int bottom = int(std::round(dh + 0.1f));
    34. int left = int(std::round(dw - 0.1f));
    35. int right = int(std::round(dw + 0.1f));
    36. cv::copyMakeBorder(tmp, out_image, top, bottom, left, right, cv::BORDER_CONSTANT, color);
    37. return 1.0f / r;
    38. }
    39. float* Yolo::blobFromImage(cv::Mat& img) {
    40. float* blob = new float[img.total() * 3];
    41. int channels = 3;
    42. int img_h = img.rows;
    43. int img_w = img.cols;
    44. for (size_t c = 0; c < channels; c++) {
    45. for (size_t h = 0; h < img_h; h++) {
    46. for (size_t w = 0; w < img_w; w++) {
    47. blob[c * img_w * img_h + h * img_w + w] = (float)img.at<cv::Vec3b>(h, w)[c] / 255.0;
    48. }
    49. }
    50. }
    51. return blob;
    52. }
    53. void Yolo::draw_objects(const cv::Mat& img, float* Boxes, int* ClassIndexs, int* BboxNum, float* Scores) {
    54. for (int j = 0; j < BboxNum[0]; j++) {
    55. cv::Rect rect(Boxes[j * 4], Boxes[j * 4 + 1], Boxes[j * 4 + 2], Boxes[j * 4 + 3]);
    56. cv::rectangle(img, rect, cv::Scalar(0x27, 0xC1, 0x36), 2);
    57. cv::putText(
    58. img,
    59. std::to_string(ClassIndexs[j])+":"+std::to_string(Scores[j]),
    60. cv::Point(rect.x, rect.y - 1),
    61. cv::FONT_HERSHEY_PLAIN,
    62. 1.2,
    63. cv::Scalar(0xFF, 0xFF, 0xFF),
    64. 2);
    65. //cv::imwrite("result.jpg", img);
    66. }
    67. }
    68. Yolo::Yolo(char* model_path) {
    69. ifstream ifile(model_path, ios::in | ios::binary);
    70. if (!ifile) {
    71. cout << "read serialized file failed\n";
    72. std::abort();
    73. }
    74. ifile.seekg(0, ios::end);
    75. const int mdsize = ifile.tellg();
    76. ifile.clear();
    77. ifile.seekg(0, ios::beg);
    78. vector<char> buf(mdsize);
    79. ifile.read(&buf[0], mdsize);
    80. ifile.close();
    81. cout << "model size: " << mdsize << endl;
    82. runtime = nvinfer1::createInferRuntime(gLogger);
    83. initLibNvInferPlugins(&gLogger, "");
    84. engine = runtime->deserializeCudaEngine((void*)&buf[0], mdsize, nullptr);
    85. auto in_dims = engine->getBindingDimensions(engine->getBindingIndex("images"));
    86. iH = in_dims.d[2];
    87. iW = in_dims.d[3];
    88. in_size = 1;
    89. for (int j = 0; j < in_dims.nbDims; j++) {
    90. in_size *= in_dims.d[j];
    91. }
    92. auto out_dims1 = engine->getBindingDimensions(engine->getBindingIndex("num_dets"));
    93. out_size1 = 1;
    94. for (int j = 0; j < out_dims1.nbDims; j++) {
    95. out_size1 *= out_dims1.d[j];
    96. }
    97. auto out_dims2 = engine->getBindingDimensions(engine->getBindingIndex("det_boxes"));
    98. out_size2 = 1;
    99. for (int j = 0; j < out_dims2.nbDims; j++) {
    100. out_size2 *= out_dims2.d[j];
    101. }
    102. auto out_dims3 = engine->getBindingDimensions(engine->getBindingIndex("det_scores"));
    103. out_size3 = 1;
    104. for (int j = 0; j < out_dims3.nbDims; j++) {
    105. out_size3 *= out_dims3.d[j];
    106. }
    107. auto out_dims4 = engine->getBindingDimensions(engine->getBindingIndex("det_classes"));
    108. out_size4 = 1;
    109. for (int j = 0; j < out_dims4.nbDims; j++) {
    110. out_size4 *= out_dims4.d[j];
    111. }
    112. context = engine->createExecutionContext();
    113. if (!context) {
    114. cout << "create execution context failed\n";
    115. std::abort();
    116. }
    117. cudaError_t state;
    118. state = cudaMalloc(&buffs[0], in_size * sizeof(float));
    119. if (state) {
    120. cout << "allocate memory failed\n";
    121. std::abort();
    122. }
    123. state = cudaMalloc(&buffs[1], out_size1 * sizeof(int));
    124. if (state) {
    125. cout << "allocate memory failed\n";
    126. std::abort();
    127. }
    128. state = cudaMalloc(&buffs[2], out_size2 * sizeof(float));
    129. if (state) {
    130. cout << "allocate memory failed\n";
    131. std::abort();
    132. }
    133. state = cudaMalloc(&buffs[3], out_size3 * sizeof(float));
    134. if (state) {
    135. cout << "allocate memory failed\n";
    136. std::abort();
    137. }
    138. state = cudaMalloc(&buffs[4], out_size4 * sizeof(int));
    139. if (state) {
    140. cout << "allocate memory failed\n";
    141. std::abort();
    142. }
    143. state = cudaStreamCreate(&stream);
    144. if (state) {
    145. cout << "create stream failed\n";
    146. std::abort();
    147. }
    148. }
    149. void Yolo::Infer(
    150. int aWidth,
    151. int aHeight,
    152. int aChannel,
    153. unsigned char* aBytes,
    154. float* Boxes,
    155. int* ClassIndexs,
    156. int* BboxNum,
    157. float* Scores) {
    158. cv::Mat img(aHeight, aWidth, CV_MAKETYPE(CV_8U, aChannel), aBytes);
    159. cv::Mat pr_img;
    160. float scale = letterbox(img, pr_img, {iW, iH}, 32, {114, 114, 114}, true);
    161. cv::cvtColor(pr_img, pr_img, cv::COLOR_BGR2RGB);
    162. float* blob = blobFromImage(pr_img);
    163. static int* num_dets = new int[out_size1];
    164. static float* det_boxes = new float[out_size2];
    165. static float* det_scores = new float[out_size3];
    166. static int* det_classes = new int[out_size4];
    167. cudaError_t state =
    168. cudaMemcpyAsync(buffs[0], &blob[0], in_size * sizeof(float), cudaMemcpyHostToDevice, stream);
    169. if (state) {
    170. cout << "transmit to device failed\n";
    171. std::abort();
    172. }
    173. context->enqueueV2(&buffs[0], stream, nullptr);
    174. state =
    175. cudaMemcpyAsync(num_dets, buffs[1], out_size1 * sizeof(int), cudaMemcpyDeviceToHost, stream);
    176. if (state) {
    177. cout << "transmit to host failed \n";
    178. std::abort();
    179. }
    180. state = cudaMemcpyAsync(
    181. det_boxes, buffs[2], out_size2 * sizeof(float), cudaMemcpyDeviceToHost, stream);
    182. if (state) {
    183. cout << "transmit to host failed \n";
    184. std::abort();
    185. }
    186. state = cudaMemcpyAsync(
    187. det_scores, buffs[3], out_size3 * sizeof(float), cudaMemcpyDeviceToHost, stream);
    188. if (state) {
    189. cout << "transmit to host failed \n";
    190. std::abort();
    191. }
    192. state = cudaMemcpyAsync(
    193. det_classes, buffs[4], out_size4 * sizeof(int), cudaMemcpyDeviceToHost, stream);
    194. if (state) {
    195. cout << "transmit to host failed \n";
    196. std::abort();
    197. }
    198. BboxNum[0] = num_dets[0];
    199. int img_w = img.cols;
    200. int img_h = img.rows;
    201. int x_offset = (iW * scale - img_w) / 2;
    202. int y_offset = (iH * scale - img_h) / 2;
    203. for (size_t i = 0; i < num_dets[0]; i++) {
    204. float x0 = (det_boxes[i * 4]) * scale - x_offset;
    205. float y0 = (det_boxes[i * 4 + 1]) * scale - y_offset;
    206. float x1 = (det_boxes[i * 4 + 2]) * scale - x_offset;
    207. float y1 = (det_boxes[i * 4 + 3]) * scale - y_offset;
    208. x0 = std::max(std::min(x0, (float)(img_w - 1)), 0.f);
    209. y0 = std::max(std::min(y0, (float)(img_h - 1)), 0.f);
    210. x1 = std::max(std::min(x1, (float)(img_w - 1)), 0.f);
    211. y1 = std::max(std::min(y1, (float)(img_h - 1)), 0.f);
    212. Boxes[i * 4] = x0;
    213. Boxes[i * 4 + 1] = y0;
    214. Boxes[i * 4 + 2] = x1 - x0;
    215. Boxes[i * 4 + 3] = y1 - y0;
    216. ClassIndexs[i] = det_classes[i];
    217. Scores[i] = det_scores[i];
    218. }
    219. delete blob;
    220. }
    221. Yolo::~Yolo() {
    222. cudaStreamSynchronize(stream);
    223. cudaFree(buffs[0]);
    224. cudaFree(buffs[1]);
    225. cudaFree(buffs[2]);
    226. cudaFree(buffs[3]);
    227. cudaFree(buffs[4]);
    228. cudaStreamDestroy(stream);
    229. context->destroy();
    230. engine->destroy();
    231. runtime->destroy();
    232. }

     listenerMat.cpp

    1. // 1.包含头文件;
    2. #include "rclcpp/rclcpp.hpp"
    3. #include "std_msgs/msg/string.hpp"
    4. #include <cv_bridge/cv_bridge.h>
    5. #include <sensor_msgs/msg/image.hpp>
    6. #include <opencv4/opencv2/opencv.hpp>
    7. #include "utils.h"
    8. #include "kalmanboxtracker.h"
    9. #include "sort.h"
    10. #include <algorithm>
    11. #include <vector>
    12. #include <iostream>
    13. #include "std_msgs/msg/string.hpp"
    14. using namespace std::chrono_literals;
    15. using namespace std::chrono_literals;
    16. using std::placeholders::_1;
    17. //using std::placeholders::_1;
    18. using std::placeholders::_2;
    19. #include "yolo.h"
    20. Yolo *myyolo;
    21. sort *mot_tracker;
    22. std::vector<cv::Vec3b> colors;
    23. std::string msgstr = "";
    24. cv::Mat detectResultMat = cv::Mat::zeros(1080,720,CV_8UC3);
    25. void filter(float* Boxes,int* ClassIndexs,int* BboxNum,float* Scores,
    26. float conf_thres, std::vector<int> classes,float *newBoxes,
    27. int *newClassIndexs,int *newBboxNum,float *newScores)
    28. {
    29. int count = 0;
    30. for (int i =0;i<BboxNum[0];i++) {
    31. if (Scores[i]>conf_thres){
    32. std::vector<int>::iterator iter=std::find(classes.begin(),classes.end(),ClassIndexs[i]);
    33. if ( iter!=classes.end())
    34. {
    35. //cout << "Not found" << endl;
    36. for (int j=0;j<4;j++) {
    37. newBoxes[count*4+j]=Boxes[i*4+j];
    38. }
    39. newClassIndexs[count]=ClassIndexs[i];
    40. newScores[count]=Scores[i];
    41. count++;
    42. }
    43. }
    44. }
    45. newBboxNum[0]=count;
    46. }
    47. // 3.定义节点类;
    48. class MinimalSubscriber : public rclcpp::Node
    49. {
    50. public:
    51. MinimalSubscriber(std::string name)
    52. : Node(name)
    53. {
    54. srand(time(0));
    55. for (size_t i = 0; i < 100; i++)
    56. colors.push_back(cv::Vec3b(rand() % 255, rand() % 255, rand() % 255));
    57. mot_tracker = new sort(5, 4, 0.25);
    58. // 3-1.创建订阅方;
    59. //subscription_ = this->create_subscription<sensor_msgs::msg::CompressedImage>("pubImageTopic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
    60. subscription_ = this->create_subscription<sensor_msgs::msg::CompressedImage>("pubImageTopic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
    61. // 3-1.创建发布方;
    62. msgPublisher_ = this->create_publisher<std_msgs::msg::String>("detectResultMsgtopic", 10);
    63. // 3-2.创建定时器;
    64. msgTimer = this->create_wall_timer(50ms, std::bind(&MinimalSubscriber::msg_timer_callback, this));
    65. //mat topic
    66. matPublisher_ = this->create_publisher<sensor_msgs::msg::CompressedImage>("detectResultMatTopic", 10);
    67. matTimer = this->create_wall_timer(50ms, std::bind(&MinimalSubscriber::mat_timer_callback, this));
    68. }
    69. private:
    70. // 3-2.处理订阅到的消息;
    71. //rclcpp::Subscription<sensor_msgs::msg::CompressedImage> subscription_;
    72. rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr subscription_;
    73. //void topic_callback(const sensor_msgs::msg::CompressedImage & msg) const
    74. rclcpp::TimerBase::SharedPtr msgTimer;
    75. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr msgPublisher_;
    76. //std_msgs::msg::String detectResultMessage;// = std_msgs::msg::String();
    77. //detectResultMessage.data = "null";
    78. rclcpp::TimerBase::SharedPtr matTimer;
    79. rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr matPublisher_;
    80. //sensor_msgs::msg::CompressedImage::SharedPtr detect_result_img_compressed_;// = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", des1080).toCompressedImageMsg();
    81. void msg_timer_callback(){
    82. // 3-3.组织消息并发布。
    83. auto detectResultMessage = std_msgs::msg::String();
    84. detectResultMessage.data = msgstr;
    85. RCLCPP_INFO(this->get_logger(), "发布的消息:'%s'", detectResultMessage.data.c_str());
    86. msgPublisher_ ->publish(detectResultMessage);
    87. }
    88. void mat_timer_callback(){
    89. sensor_msgs::msg::CompressedImage::SharedPtr detect_result_img_compressed_ = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", detectResultMat).toCompressedImageMsg();
    90. //RCLCPP_INFO(this->get_logger(), "发布的消息:检测图片");
    91. this->matPublisher_ ->publish(*detect_result_img_compressed_);
    92. }
    93. void topic_callback(const sensor_msgs::msg::CompressedImage::ConstPtr msg) const
    94. {
    95. try
    96. {
    97. cv_bridge::CvImagePtr cv_ptr_compressed = cv_bridge::toCvCopy(msg,sensor_msgs::image_encodings::BGR8);
    98. cv::Mat imgCallback = cv_ptr_compressed->image;
    99. //cv::imshow("imgCallback",imgCallback);
    100. //cv::waitKey(1);
    101. cv::Mat des1080;
    102. //cv::resize(imgCallback, des1080, cv::Size(1920, 1080), 0, 0, cv::INTER_NEAREST);
    103. cv::resize(imgCallback, des1080, cv::Size(1080, 720), 0, 0, cv::INTER_NEAREST);
    104. //std::cout<<"cv_ptr_compressed: "<<cv_ptr_compressed->image.cols<<" h: "<<cv_ptr_compressed->image.rows<<std::endl;
    105. //std::cout<<des1080.size()<<std::endl;
    106. float* Boxes = new float[400];
    107. int* BboxNum = new int[1];
    108. int* ClassIndexs = new int[100];
    109. float* Scores = new float[100];
    110. //auto start = std::chrono::system_clock::now();
    111. myyolo->Infer(des1080.cols, des1080.rows, des1080.channels(), des1080.data, Boxes, ClassIndexs, BboxNum,Scores);
    112. //auto end = std::chrono::system_clock::now();
    113. //std::cout<<std::chrono::duration_cast<std::chrono::milliseconds>(end-start).count()<<"ms"<<std::endl;
    114. //myyolo->draw_objects(des1080, Boxes, ClassIndexs, BboxNum, Scores);
    115. float newBoxes[400];
    116. int newBboxNum[1];
    117. int newClassIndexs[100];
    118. float newScores[100];
    119. float conf_thres = 0.4;
    120. std::vector<int> classes;
    121. //classes.push_back(1);//识别车
    122. classes.push_back(0);//识别人
    123. filter(Boxes, ClassIndexs, BboxNum,Scores,conf_thres,classes,newBoxes,newClassIndexs,newBboxNum,newScores);
    124. std::vector<cv::Rect> detections;
    125. for (int i =0; i< newBboxNum[0]; i++){
    126. cv::Rect rect(newBoxes[i * 4], newBoxes[i * 4 + 1], newBoxes[i * 4 + 2], newBoxes[i * 4 + 3]);
    127. detections.push_back(rect);
    128. }
    129. std::vector<std::vector<float>> trackers = mot_tracker->update(detections);
    130. //qDebug()<<trackers;
    131. std::string sendstr = "";
    132. if(!trackers.empty()){
    133. for (auto tracker : trackers)
    134. {
    135. cv::rectangle(des1080, cv::Rect(tracker[0], tracker[1],
    136. tracker[2]- tracker[0], tracker[3]- tracker[1]),
    137. colors[int(tracker[4])%100], 2);
    138. cv::putText(des1080,std::to_string(int(tracker[4])),
    139. cv::Point(tracker[0], tracker[1]),
    140. cv::FONT_HERSHEY_PLAIN,1.5,
    141. colors[int(tracker[4])%100],
    142. 2);
    143. std::string objnum = std::to_string(int(tracker[4]));
    144. std::string x0 = std::to_string(int(tracker[0]));
    145. std::string y0 = std::to_string(int(tracker[1]));
    146. std::string x1 = std::to_string(int(tracker[2]));
    147. std::string y1 = std::to_string(int(tracker[3]));
    148. sendstr = sendstr+objnum+","+x0+","+y0+","+x1+","+y1+";";
    149. }
    150. //this->detectResultMessage.data = std::to_string(84);
    151. //msgstr = "sddh15151515";
    152. //std::string str
    153. msgstr = sendstr;
    154. }
    155. else{
    156. //msgstr = "null";
    157. msgstr = sendstr;
    158. }
    159. cv::imshow("des1080",des1080);
    160. cv::waitKey(1);
    161. detectResultMat = des1080;
    162. //auto end = std::chrono::system_clock::now();
    163. //std::cout<<std::chrono::duration_cast<std::chrono::milliseconds>(end-start).count()<<"ms"<<std::endl;
    164. }
    165. catch (cv_bridge::Exception& e)
    166. {
    167. std::cout<<"Could not convert !!!"<<std::endl;
    168. //cv::Mat des1080;
    169. //detectResultMat = des1080;
    170. }
    171. }
    172. };
    173. int main(int argc, char * argv[])
    174. {
    175. std::string str = "./src/detect_topic/src/yolov7-tiny-nms.trt";
    176. char* chr = const_cast(str.c_str());
    177. myyolo = new Yolo(chr);
    178. // 2.初始化 ROS2 客户端;
    179. rclcpp::init(argc, argv);
    180. // 4.调用spin函数,并传入节点对象指针。
    181. auto node = std::make_shared<MinimalSubscriber>("detect");
    182. rclcpp::spin(node);
    183. //rclcpp::spin(std::make_shared<MinimalSubscriber>());
    184. // 5.释放资源;
    185. rclcpp::shutdown();
    186. return 0;
    187. }

    package.xml

    1. <?xml version="1.0"?>
    2. <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
    3. <package format="3">
    4. <name>detect_topic</name>
    5. <version>0.0.0</version>
    6. <description>TODO: Package description</description>
    7. <maintainer email="1187506013@qq.com">tuya</maintainer>
    8. <license>TODO: License declaration</license>
    9. <buildtool_depend>ament_cmake</buildtool_depend>
    10. <depend>rclcpp</depend>
    11. <depend>std_msgs</depend>
    12. <test_depend>ament_lint_auto</test_depend>
    13. <test_depend>ament_lint_common</test_depend>
    14. <export>
    15. <build_type>ament_cmake</build_type>
    16. </export>
    17. </package>

    CMakeLists.txt

    1. cmake_minimum_required(VERSION 3.8)
    2. project(detect_topic)
    3. add_definitions(-std=c++14)
    4. # Default to C++14
    5. #if(NOT CMAKE_CXX_STANDARD)
    6. set(CMAKE_CXX_STANDARD 14)
    7. #endif()
    8. if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
    9. add_compile_options(-Wall -Wextra -Wpedantic)
    10. endif()
    11. # find dependencies
    12. find_package(ament_cmake REQUIRED)
    13. find_package(rclcpp REQUIRED)
    14. find_package(std_msgs REQUIRED)
    15. find_package(cv_bridge REQUIRED)
    16. find_package(image_transport)
    17. find_package(sensor_msgs REQUIRED)
    18. find_package(CUDA REQUIRED)
    19. include_directories(${CUDA_INCLUDE_DIRS})
    20. include_directories(/usr/local/cuda/include)
    21. link_directories(/usr/local/cuda/lib64)
    22. # tensorrt
    23. include_directories(/usr/include/aarch64-linux-gnu/)
    24. link_directories(/usr/lib/aarch64-linux-gnu/)
    25. # tensorrt
    26. #include_directories(/home/tuya/TensorRT-8.6.1.6/targets/x86_64-linux-gnu/include/)
    27. #link_directories(/home/tuya/TensorRT-8.6.1.6/targets/x86_64-linux-gnu/lib/)
    28. set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Ofast -Wfatal-errors -D_MWAITXINTRIN_H_INCLUDED")
    29. add_executable(detect
    30. src/listenerMat.cpp
    31. src/yolo.h
    32. src/yolo.cpp
    33. src/hungarian.h
    34. src/hungarian.cpp
    35. src/kalmanboxtracker.h
    36. src/kalmanboxtracker.cpp
    37. src/sort.h
    38. src/sort.cpp
    39. src/utils.h
    40. src/utils.cpp
    41. )
    42. find_package(OpenCV REQUIRED)
    43. include_directories( ${OpenCV_INCLUDE_DIRS})
    44. target_link_libraries(detect ${OpenCV_LIBS})
    45. # ros
    46. target_link_libraries(detect
    47. ${rclcpp_LIBRARIES}
    48. )
    49. target_link_libraries(detect nvinfer)
    50. target_link_libraries(detect nvinfer_plugin)
    51. target_link_libraries(detect cudart)
    52. ament_target_dependencies(detect
    53. rclcpp
    54. std_msgs
    55. sensor_msgs
    56. cv_bridge
    57. OpenCV
    58. image_transport
    59. )
    60. # 安装可执行文件
    61. install(TARGETS detect
    62. DESTINATION lib/${PROJECT_NAME}
    63. )
    64. ament_package()

    SORT代码

    sort demo_涂鸦c的博客-CSDN博客

  • 相关阅读:
    自动化物流运输设备模组要选择哪种类型?
    【JAVA】:万字长篇带你了解JAVA并发编程【一】
    【Java集合类面试二十】、请介绍LinkedHashMap的底层原理
    【JavaEE】_Spring MVC项目之建立连接
    Git 行结束符:LF will be replaced by CRLF the next time Git touches it问题解决指南
    Python接口自动化搭建过程,含request请求封装!
    分布式事务使用GlobalTransactional注解insert 报错java.sql.SQLException: 调用中的无效参数,
    spring boot入门与理解MVC三层架构
    1024网络技术命令汇总(第54课)
    吴恩达2022机器学习专项课程C2W2:实验SoftMax
  • 原文地址:https://blog.csdn.net/qq_16377055/article/details/133787595