赞
踩
由于项目需要,需要在指定位置和时刻调用yolov4进行识别,其余时间不需要识别。因此参考网上的教程,自己改写了ros下对yolov4的调用,并写成了单独的功能包,可以通过接收话题的形式触发网络进行识别,移植性强。
运行环境:
ubuntu16.04
ros kinetic
opencv2.4.10(项目需要)
无gpu,纯cpu运行
项目开始
首先先把yolov4的darknet下载下来
git clone https://github.com/AlexeyAB/darknet.git
进入该文件夹
cd darknet
里面有一个Makefile文件,打开后在开头位置那里把opencv和libso置为1,其余不动
GPU=0
CUDNN=0
CUDNN_HALF=0
OPENCV=1
AVX=0
OPENMP=0
LIBSO=1
ZED_CAMERA=0
ZED_CAMERA_v2_8=0
由于没用到GPU,所以修改完后直接运行了 make,注意提前把yolov4.weights权重文件下载到darknet根目录下,这个网上比较多,大家自行找一下。
make
编译完成后可以直接在当前终端执行以下指令进行验证
./darknet detect cfg/yolov4.cfg yolov4.weights data/dog.jpg
纯CPU运行有点慢,我在虚拟机跑是22s左右,如果出现结果就证明可以使用了。
现在开始制作自己的功能包,这部分教程代码参考了这篇博文,然后写成了ros的一个功能包,方便直接使用。
这里需要几个文件:
1、刚才编译成功后在darknet文件夹下会出现libdarknet.so文件、
2、darknet/include下面有yolo_v2_class.hpp文件
3、coco.names、yolov4.cfg、yolov4.weights这三个文件,(在darknet目录下搜索一下就找到了)。
开始新建功能包
我在ros下用roboware进行代码编写,这个IDE会自动生成cmakelist文件,比较方便。
首先新建功能包 ros_yolo_cpp
1、然后在功能包下新建include文件夹,存放yolo_v2_class.hpp
2、新建cfg文件夹,存放coco.names、yolov4.cfg、yolov4.weights这三个文件
3、新建lib文件夹,存放动态链接库libdarknet.so文件
4、新建src文件,并在src里面新建cpp文件,开始写代码。文件名为ros_yolo_cpp_node.cpp
5、修改Cmakelist文件夹
5.1、首先在开头那里取消c++11的注释
5.2、find_package()这里添加一些常用的依赖。主要是OpenCV得有。
roscpp pcl_ros sensor_msgs std_msgs OpenCV image_transport cv_bridge
5.3、include_directories()这里添加opencv的路径
${OpenCV_INCLUDE_DIRS}
5.4、添加动态链接库的路径,这里我用的是绝对路径
link_directories(/home/gmq/catkin_ws/src/ros_yolo_cpp/lib)
5.5、add_executable()这里把用到的文件名字写出来
add_executable(ros_yolo_cpp_node
src/ros_yolo_cpp_node.cpp
include/yolo_v2_class.hpp
)
5.6、target_link_libraries()这里添加opencv的库,以及刚才的动态链接库
target_link_libraries(ros_yolo_cpp_node
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
darknet
)
注意:原来的动态链接库名字是libdarknet.so,这里要把lib和.so去掉。
6、开始真正写代码
这里参考了别人的代码,进行了一部分修改,主要是对图片进行处理。完整代码如下:
#include <ros/ros.h>
#include<string>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/highgui.hpp>
#include <vector>
#include <fstream>
#include <sys/time.h>
#include<sensor_msgs/image_encodings.h>
#include<std_msgs/Header.h>
#include<cv_bridge/cv_bridge.h>
#include<iostream>
#include "yolo_v2_class.hpp"
using namespace std;
using namespace cv;
bool e=true;
static ros::Subscriber image_sub;
static ros::Publisher detect_pub;
string classesFile = "./yolo/coco.names";
string modelConfig = "./yolo/yolov4.cfg";
string modelWeights = "./yolo/yolov4.weights";
//加载网络模型,0是指定第一块GPU
Detector detector(modelConfig, modelWeights, 0);
//画出检测框和相关信息
void DrawBoxes(Mat &frame, vector<string> classes, int classId, float conf, int left, int top, int right, int bottom)
{
//画检测框
rectangle(frame, Point(left, top), Point(right, bottom), Scalar(255, 178, 50), 3);
//该检测框对应的类别和置信度
string label = format("%.2f", conf);
if (!classes.empty())
{
CV_Assert(classId < (int)classes.size());
label = classes[classId] + ":" + label;
}
//将标签显示在检测框顶部
int baseLine;
Size labelSize = getTextSize(label, FONT_HERSHEY_SIMPLEX, 0.5, 1, &baseLine);
top = max(top, labelSize.height);
rectangle(frame, Point(left, top - round(1.5*labelSize.height)), Point(left + round(1.5*labelSize.width), top + baseLine), Scalar(255, 255, 255), FILLED);
putText(frame, label, Point(left, top), FONT_HERSHEY_SIMPLEX, 0.75, Scalar(0, 0, 0), 1);
}
//画出检测结果
void Drawer(Mat &frame, vector<bbox_t> outs, vector<string> classes)
{
//获取所有最佳检测框信息
for (int i = 0; i < outs.size(); i++)
{
DrawBoxes(frame, classes, outs[i].obj_id, outs[i].prob, outs[i].x, outs[i].y,
outs[i].x + outs[i].w, outs[i].y + outs[i].h);
}
}
void image_callback(const sensor_msgs::ImageConstPtr &in_image)
{
if(e==true)
{
e=false;
struct timeval tv1,tv2;
long long T;
//image -->mat
cv_bridge::CvImagePtr frame;
frame=cv_bridge::toCvCopy(in_image,sensor_msgs::image_encodings::BGR8);
gettimeofday(&tv1,NULL);
/* //Mat图像转为yolo输入格式
shared_ptr<image_t> detImg = detector.mat_to_image_resize(frame->image);
//前向预测
vector<bbox_t> outs = detector.detect_resized(*detImg, frame->image.cols, frame->image.rows, 0.25);
// 以上{}内的代码可以用
*/
vector<bbox_t> outs = detector.detect(frame->image, 0.25);
//加载类别名
vector<string> classes;
ifstream ifs(classesFile.c_str());
string line;
while (getline(ifs, line)) classes.push_back(line);
//画图
Drawer(frame->image, outs, classes);
gettimeofday(&tv2,NULL);
T=(tv2.tv_sec - tv1.tv_sec)*1000 + (tv2.tv_usec -tv1.tv_usec)/1000;
cout<<T<<"ms"<<endl;
detect_pub.publish(frame->toImageMsg());
}
else
{
cout<<"error is true"<<endl;
}
}
int main(int argc,char**argv)
{
ros::init(argc,argv,"ros_yolo_cpp");
ros::NodeHandle nh;
detect_pub=nh.advertise<sensor_msgs::Image>("detect_img",1);
image_sub=nh.subscribe("/src_image",1,image_callback);
ros::spin();
return 0;
}
注意: 根据自己路径对coco.names这些的读入路径进行修改,以及读取图片和存放结果的路径。
修改完后即可在工作空间下使用catkin_make
进行编译了。
编译遇到的问题:编译时一直提示我mat_to_image_resize
函数不是detector
的函数,我去查看yolo_v2_class.hpp文件,发现`mat_to_image_resize函数是定义在
#ifdef OPENCV
#endif //OPENCV
之间,没太懂这里的意思,所以就把yolo_v2_class.hpp文件里面的这两句 ifdef 和endif注释掉了。注释之后再次catkin_make就通过了。希望能有大佬解释一下,不胜感激!
然后运行
roscore
rosrun ros_yolo_cpp ros_yolo_cpp_node
即可在输出路径下查看到识别结果。
若要更换 yolo-fastest 方法进行识别,速度快。
1、首先把yolo-fastest的makefile修改,编译生成新的.so文件,然后进行lib下的替换;
2、再把之前的coco.names、yolov4.cfg、yolov4.weights三个文件进行替换:
把yolo-fastest下data下的voc.names 替换coco.names,把VOC下的yolo-fastest-xl.weights 和 yolo-fastest-xl.cfg 替换yolov4.cfg、yolov4.weights。在代码中修改一下路径,即可进行重新使用。
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。