目录
- 一、添加ROS工作空间,把源码放到catkin_ws/src目录下
- 二、改CMakeLists.txt和添加package.xml
- 三、源码添加ROS头文件和创建ROS节点
- 四、源码添加ROS话题发布数据
一、添加ROS工作空间,把源码放到catkin_ws/src目录下
目录结构与一般的ROS工作空间类似,把yolov5的包放在catkin_ws/src
下,作为一个ROS的功能包。
二、改CMakeLists.txt和添加package.xml
2.1 修改CMakeLists.txt
一般而言,C++版本的yolov5都有CMakeLists.txt,因此需要在其中添加ROS的环境,生成ROS的可执行文件。
2.1.1 添加ROS的catkin包
find_package(catkin REQUIRED
COMPONENTS
roscpp
nav_msgs
sensor_msgs
std_msgs
image_transport
message_generation
cv_bridge
tf2
)
2.1.2 添加自定义msg消息类型
add_message_files(
FILES
single_res.msg
multi_res.msg
yolo_detection.msg
)
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)
2.1.3 添加当前包所依赖的其他 Catkin 包
catkin_package(
CATKIN_DEPENDS
roscpp
nav_msgs
image_transport
std_msgs
cv_bridge
sensor_msgs
message_runtime
tf2
)
CATKIN_DEPENDS
:列出当前包所依赖的其他 Catkin 包。这些依赖将自动添加到其他包需要链接和包含当前包时所需的依赖中。
2.1.4 添加依赖库
target_link_libraries(yolov5s ${catkin_LIBRARIES})
至此,CMakeLists.txt
文件修改完成!
注意:CMakeLists.txt
文件中已经有了生成yolov5的可执行文件的命令,不需要额外再生成!
add_executable(yolov5s ${PROJECT_SOURCE_DIR}/yolov5s.cpp ${PROJECT_SOURCE_DIR}/videoCapture.cpp)
2.1.5 完整CMakeLists.txt
文件
cmake_minimum_required(VERSION 2.6)
project(yolov5)
add_definitions(-std=c++11)
option(CUDA_USE_STATIC_CUDA_RUNTIME OFF)
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_BUILD_TYPE Debug)
#set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -O0")
find_package(CUDA REQUIRED)
find_package(catkin REQUIRED
COMPONENTS
roscpp
nav_msgs
sensor_msgs
std_msgs
image_transport
message_generation
cv_bridge
tf2
)
#find_package(cv_bridge)
#include_directories(${cv_bridge_INCLUDE_DIRS})
find_package(OpenCV 4)
include_directories(${OpenCV_INCLUDE_DIRS})
set(CUDA_NVCC_PLAGS ${CUDA_NVCC_PLAGS};-std=c++11;-g;-G;-gencode;arch=compute_30;code=sm_30)
include_directories(${PROJECT_SOURCE_DIR}/include ${catkin_INCLUDE_DIRS})
if (CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64")
message("embed_platform on")
include_directories(/usr/local/cuda/targets/aarch64-linux/include)
link_directories(/usr/local/cuda/targets/aarch64-linux/lib)
else()
message("embed_platform off")
include_directories(/usr/local/cuda/include)
link_directories(/usr/local/cuda/lib64)
endif()
add_message_files(
FILES
single_res.msg
multi_res.msg
yolo_detection.msg
)
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)
catkin_package(
CATKIN_DEPENDS
roscpp
nav_msgs
image_transport
std_msgs
cv_bridge
sensor_msgs
message_runtime
tf2
)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall -Ofast -Wfatal-errors -D_MWAITXINTRIN_H_INCLUDED")
cuda_add_library(yololayer SHARED ${PROJECT_SOURCE_DIR}/yololayer.cu)
message("${OpenCV_INCLUDE_DIRS}")
add_executable(yolov5s ${PROJECT_SOURCE_DIR}/yolov5s.cpp ${PROJECT_SOURCE_DIR}/videoCapture.cpp)
target_link_libraries(yolov5s nvinfer)
target_link_libraries(yolov5s cudart)
target_link_libraries(yolov5s yololayer)
target_link_libraries(yolov5s ${OpenCV_LIBRARIES})
target_link_libraries(yolov5s ${catkin_LIBRARIES})
#target_link_libraries(yolov5s ${cv_bridge_LIBRARIES})
add_definitions(-O2 -pthread)
2.2 添加package.xml文件
<?xml version="1.0"?>
<package format="2">
<name>yolov5</name>
<version>1.17.1</version>
<description>
yolo v5.
</description>
<author>Brian Gerkey, Tony Pratkanis</author>
<author>contradict@gmail.com</author>
<maintainer email="davidvlu@gmail.com">David V. Lu!!</maintainer>
<maintainer email="mfergs7@gmail.com">Michael Ferguson</maintainer>
<maintainer email="ahoy@fetchrobotics.com">Aaron Hoy</maintainer>
<url>http://wiki.ros.org/map_server</url>
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>nav_msgs</depend>
<depend>message_generation</depend>
<depend>message_runtime</depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>image_transport</depend>
<depend>cv_bridge</depend>
<depend>tf2</depend>
</package>
该文件中主要在<depend>
标签中添加所依赖的ROS包即可!
三、源码添加ROS头文件和创建ROS节点
3.1 添加ROS头文件
#include <ros/ros.h>
#include "nav_msgs/MapMetaData.h"
#include <sensor_msgs/CameraInfo.h>
#include <image_transport/image_transport.h> // ROS的图像发布器
#include <cv_bridge/cv_bridge.h>
#include "yolov5/yolo_detection.h" // 自定义消息文件
#include "yolov5/single_res.h" // 自定义消息文件
将ROS的头文件包含在yolov5.cpp
具体实现文件中。
3.2 创建并运行ROS节点
在主函数中添加下面代码,创建ROS节点。
int main(int argc, char** argv) {
ros::init(argc, argv, "yolov5");
xxx
回到工作空间目录下
cd ~/catkin_yolov5/src
重新编译
catkin_make
添加工作空间环境
source devel/setup.bash
用ROS命令启动程序
roscore
rosrun yolov5 yolov5s
至此,已经将一个普通的C++程序改造为一个ROS程序,并且可以以ROS命令启动该程序!
四、源码添加ROS话题发布数据
将普通C++程序改为ROS程序的主要目的是将其纳入ROS通信体系,这样其计算结果以ROS的topic形式发送出来,也可接收其它ROS节点的数据。
4.1 创建发布对象
ros::NodeHandle nh; // 节点句柄
ros::Publisher yolo_res_pub = nh.advertise<yolov5::yolo_detection>("yolo_res",1); //自定义消息话题
image_transport::ImageTransport it(nh); // ROS的图像发布器的handle
image_transport::Publisher pub = it.advertise("image_yolo", 1); // ROS的图像发布器
4.2 发布ROS消息
yolov5::yolo_detection detect_res; // 自定义消息类型的数据
yolov5::single_res s_res;
yolov5::multi_res m_res;
for (int b = 0; b < fcount; b++) { // batch_res为当前帧所检测的所有类,二维vector
auto& res = batch_res[b]; // res为当前帧所检测的某一类的所有框,一维vector
for (size_t j = 0; j < res.size(); j++) { // 提取boundingbox
s_res.conf = res[j].conf;
s_res.class_id = res[j].class_id;
s_res.bbox[0] = res[j].bbox[0];
s_res.bbox[1] = res[j].bbox[1];
s_res.bbox[2] = res[j].bbox[2];
s_res.bbox[3] = res[j].bbox[3];
m_res.single_res_arrary.push_back(s_res);
}
detect_res.yolo_res.push_back(m_res);
m_res.single_res_arrary.clear();
// 将cv::mat数据类型转换为ROS的图像类型,这里用指针,速度更快!
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", pr_img).toImageMsg();
pub.publish(msg);
}
yolo_res_pub.publish(detect_res); // 发布所有类别的框的消息
detect_res.yolo_res.clear(); // 清空