本系统的基本实现机理如下:
1)yolov8检测部分
系统的智能检测部分将使用python和yolo8来实现,具体是通过网络摄像头的rtsp视频流来推流给模型进行识别。对于检测的结果,可以通过鼠标点击的方式来选择具体追踪的目标,并且计算追踪目标的中心点。
2)程序通信部分
由于检测部分和云台的控制部分是两部分的程序,并且分别是用python和c++编写的,所以如果要让检测部分的结果传输给控制部分,就需要借助ros的话题消息订阅机制,该机制能够实现不同编程语言之间的程序通信,而且实现较为简单。
3)云台控制部分
有了检测部分发布的跟踪物体的中心点坐标信息,就可以通过比较屏幕的中心点坐标和追踪物体的中心点坐标来实时的调整云台的姿态,进而达成跟踪的目的。
安装了Ubuntu20.04的计算机,并且安装了ros操作系统。
海康威视网络移动云台。
在介绍之前,现展示整体的工作空间的目录,以便对接下来的工作有一个清晰的脉络。
catkin_ws --> src --> yolo_pkg
yolo_pkg
├── CMakeLists.txt
├── include
├── lib
├── msg
├── package.xml
├── scripts
├── src
└── ultralytics
其中yolo_pkg为创建的功能包,包含上述三个功能。在功能包之中有include、lib、msg、scripts、src、ultralytics这几个文件夹,和CMakeLists.txt、package.xml这两个文件。
include文件夹中装着c++文件中需要用到的头文件,即.h文件。
lib文件夹中装着程序需要调用的库,通常以lib开头.so为结尾。
msg文件夹中装着ros话题订阅所需要的消息文件,为.msg结尾。
scripts文件夹中放着编写好的Python文件。
src文件夹中放着编写好的C++文件。
ultralytics文件夹中放着yolov8需要用到的模型,就是yolov8克隆下来的官方文件夹。
在catkin_ws文件夹的src中创建yolo_pkg功能包,在终端中输入以下代码,rospy和roscpp是两个需要的库,也可以后续在Cmakelist文件中添加。
catkin_create_pkg yolo_pkg rospy roscpp
对于功能包中没有的文件夹需要手动创建一下,这个无伤大雅。
功能包创建完成后将海康威视SDK中提供的头文件(.h结尾)拖入到功能包的include文件夹当中,并把提供的库文件(.so结尾)拖入到功能包中的lib文件夹下。
为了确保上述拖动的文件能被程序正确的寻找到,需要修改yolo_pkg功能包下的CMakeLists.txt文件,最主要是修改以下内容:
1. find_package(),该部分主要是让程序能够找到ros中安装的功能包,如roscpp、rospy等。
2. generate_messages(),添加自定义消息生成的依赖包。
3. add_message_files(),该部分是添加自定义的消息文件。
4. include_directories(),添加头文件的具体路径。
...修改的内容较多,不过多赘述,直接放完整的文件内容:
cmake_minimum_required(VERSION 3.0.2)
project(yolo_pkg)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
add_message_files(
FILES
yolomsg.msg
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES yolo_pkg
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
include
${catkin_INCLUDE_DIRS}
${CMAKE_SOURCE_DIR}/../devel/include/yolo_pkg
include/control_pkg
)
## Declare a C++ library
add_library(${PROJECT_NAME}
src/manual_control.cpp
)
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
link_directories(lib)
link_directories(lib/HCNetSDKCom)
add_executable(consoleMain
src/consoleMain.cpp
src/manual_control.cpp
src/auto_control.cpp
)
target_link_libraries(consoleMain
${catkin_LIBRARIES}
# 主SDK库
hcnetsdk
HCCore
PlayCtrl
# 音频相关
AudioRender
hpr
openal
# 视频相关
SuperRender
NPQos
# 组件库(来自HCNetSDKCom目录)
analyzedata
AudioIntercom
HCAlarm
HCCoreDevCfg
HCDisplay
HCGeneralCfgMgr
HCIndustry
HCPlayBack
HCPreview
HCVoiceTalk
iconv2
StreamTransClient
SystemTransform
# 加密/压缩库
crypto
ssl
z
# 系统库
pthread
dl
)
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_yolo_pkg.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
创建消息文件yolomsg.msg,放在功能包中msg文件夹下。文件的具体代码如下,主要传输的内容为云台需要移动的x,y的值:
int64 xmin
int64 ymin
int64 xmax
int64 ymax
int64 movex
int64 movey
int64 update
该部分主要是调用yolov8模型,读取用户鼠标点击指令,以及发布话题消息,使用python语言编成,具体代码如下:
#!/usr/bin/env python
import cv2
from ultralytics import YOLO
import numpy as np
import rospy
from yolo_pkg.msg import yolomsg
import threading
import queue
# 初始化ROS节点
rospy.init_node("yolo_ros_pub")
pub = rospy.Publisher("yolomsg", yolomsg, queue_size=5)
# 初始化全局变量
is_mouse_clicked = False
selected_box_idx = 0
selected_id = None
# 多线程队列
frame_queue = queue.Queue(maxsize=2)
result_queue = queue.Queue(maxsize=2)
# 鼠标回调函数
def onMouse(event,start_x,start_y, flags, param):
global is_mouse_clicked, selected_box_idx, selected_id
if event == cv2.EVENT_LBUTTONDOWN:
boxes = param['boxes']
x,y = -1,-1
x,y = start_x,start_y
if not boxes:
return
distances = [np.sqrt((x - (b[0]+b[2])/2)**2 + (y - (b[1]+b[3])/2)**2) for b in boxes]
selected_box_idx = np.argmin(distances)
selected_id = param['results'][0].boxes[selected_box_idx].id
is_mouse_clicked = True
# 视频捕获线程
def capture_thread():
cap = cv2.VideoCapture("rtsp://admin:[email protected]:554/Streaming/Channels/103?Tcp")
cap.set(cv2.CAP_PROP_BUFFERSIZE, 1)
while not rospy.is_shutdown():
success, frame = cap.read()
if success:
if frame_queue.full():
try:
frame_queue.get_nowait()
except queue.Empty:
pass
frame_queue.put(frame)
else:
rospy.logwarn("Failed to read frame from the video stream.")
rospy.sleep(1)
# 模型推理线程
def inference_thread():
model = YOLO("../ultralytics/yolov8n.pt")
while not rospy.is_shutdown():
if frame_queue.empty():
rospy.sleep(0.1)
continue
frame = frame_queue.get()
results = model.predict(frame, imgsz=320, conf=0.5, classes=[0,1,2,3], verbose=False)
if result_queue.full():
try:
result_queue.get_nowait()
except queue.Empty:
pass
result_queue.put((frame, results))
# 启动线程
threading.Thread(target=capture_thread, daemon=True).start()
threading.Thread(target=inference_thread, daemon=True).start()
# 主处理循环
rate = rospy.Rate(10)
cv2.namedWindow("YOLOv8 Inference") # 显式创建窗口
while not rospy.is_shutdown():
if result_queue.empty():
rate.sleep()
continue
frame, results = result_queue.get()
boxes = results[0].boxes.xyxy.cpu().numpy().tolist() if results[0].boxes else []
# 更新鼠标回调参数
mouse_params = {'boxes': boxes, 'results': results}
cv2.setMouseCallback("YOLOv8 Inference", onMouse, mouse_params)
# 绘制结果
annotated_frame = results[0].plot()
# 处理选中目标
if is_mouse_clicked and selected_box_idx < len(boxes):
current_id = results[0].boxes[selected_box_idx].id
if current_id == selected_id:
x1, y1, x2, y2 = boxes[selected_box_idx]
cv2.rectangle(annotated_frame, (int(x1), int(y1)), (int(x2), int(y2)), (0, 255, 0), 2)
# 发布ROS消息
msg = yolomsg()
msg.update = 1
msg.xmin = int(x1)
msg.ymin = int(y1)
msg.xmax = int(x2)
msg.ymax = int(y2)
pub.publish(msg)
else:
is_mouse_clicked = False
# 显示结果
cv2.imshow("YOLOv8 Inference", annotated_frame)
if cv2.waitKey(1) & 0xFF == ord('q'):
msg.update = 0
pub.publish(msg)
break
rate.sleep()
cv2.destroyAllWindows()
云台的移动部分使用c++进行编成,是直接在海康威视SDK中提供的示例的基础上进行修改的,主要有主程序部分、自动追踪部分和人工控制部分:
1. 主程序部分,主要是为了让用户能够对功能进行选择:
/*
* Copyright(C) 2010,Hikvision Digital Technology Co., Ltd
*
* File name��consoleMain.cpp
* Discription��
* Version ��1.0
* Author ��panyadong
* Create Date��2010_3_25
* Modification History��
*/
#ifndef __APPLE__
#include "public.h"
#include "HCNetSDK.h"
#include
#include "manual_control.h"
#include "auto_control.h"
#include "ros/ros.h"
using namespace std;
int main(int argc, char *argv[])
{
ros::init(argc,argv,"yolo_ros_sub");
NET_DVR_Init();
//Demo_SDK_Version();
NET_DVR_SetLogToFile(3, "./sdkLog");
char cUserChoose = 'r';
//Login device
NET_DVR_USER_LOGIN_INFO struLoginInfo = {0};
NET_DVR_DEVICEINFO_V40 struDeviceInfoV40 = {0};
struLoginInfo.bUseAsynLogin = false;
struLoginInfo.wPort = 8000;
memcpy(struLoginInfo.sDeviceAddress, "192.168.10.108", NET_DVR_DEV_ADDRESS_MAX_LEN);
memcpy(struLoginInfo.sUserName, "admin", NAME_LEN);
memcpy(struLoginInfo.sPassword, "hmj888", NAME_LEN);
int lUserID = NET_DVR_Login_V40(&struLoginInfo, &struDeviceInfoV40);
if (lUserID < 0)
{
printf("pyd---Login error, %d\n", NET_DVR_GetLastError());
printf("Press any key to quit...\n");
cin>>cUserChoose;
NET_DVR_Cleanup();
return HPR_ERROR;
}
while ('q' != cUserChoose)
{
printf("\n");
printf(" 1, auto control\n");
printf(" 2, manual control\n");
/*
printf("\n");
printf("Input 1, Test GetStream\n");
printf(" 2, Test Configure params\n");
printf(" 3, Test Alarm\n");
printf(" 4, Test Capture Picture\n");
printf(" 5, Test play back\n");
printf(" 6, Test Voice\n");
printf(" 7, Test SDK ability\n");
printf(" 8, Test tool interface\n");
*/
/*
printf(" 7, Test Matrix decode\n");
printf(" 8, Test PTZ\n");
printf(" 9, Test Format\n");
printf(" 0, Test Update\n");
printf(" a, Test Serial trans\n");
printf(" b, Test Configure Params\n");
printf(" c, Test VCA && IVMS\n");
*/
printf(" q, Quit.\n");
printf("Input:");
cin>>cUserChoose;
switch (cUserChoose)
{
case '1':
auto_control();
cUserChoose = 0;
break;
case '2':
manual_control(); //Setting params.
cUserChoose = 0;
break;
/*
case '1':
Demo_GetStream_V30(lUserID); //Get stream.
break;
case '2':
Demo_ConfigParams(lUserID); //Setting params.
break;
case '3':
Demo_Alarm(); //Alarm & listen.
break;
case '5':
Demo_PlayBack((int)lUserID); //record & playback
break;
case '6':
Demo_Voice();
break;
case '7':
Demo_SDK_Ability();
break;
case '8':
Demo_DVRIPByResolveSvr();
break;
*/
default:
break;
}
}
//logout
NET_DVR_Logout(lUserID);
NET_DVR_Logout_V30(lUserID);
NET_DVR_Cleanup();
return 0;
}
#endif
2. 自动追踪部分,云台可以根据鼠标的点击自动追踪物体:
#include "public.h"
#include "HCNetSDK.h"
#include
#include "auto_control.h"
#include
#include
#include
#include "ros/ros.h"
#include "yolomsg.h"
using namespace std;
int xmin = 0;
int ymin = 0;
int xmax = 0;
int ymax = 0;
int x = 0;
int y = 0;
int update = -1;
const int x_center = 1920/2;
const int y_center = 1080/2;
void doyolomsg(const yolo_pkg::yolomsg::ConstPtr& yolomsg)
{
xmin = yolomsg -> xmin;
ymin = yolomsg -> ymin;
xmax = yolomsg -> xmax;
ymax = yolomsg -> ymax;
x = int(x_center - (xmax/2 + xmin/2));
y = int(y_center - (ymax/2 + ymin/2));
update = yolomsg -> update;
ROS_INFO("需要移动:movex=%d,movey=%d",x,y);
}
int auto_control()
{
NET_DVR_Init();
long lUserID;
//login
NET_DVR_USER_LOGIN_INFO struLoginInfo = {0};
NET_DVR_DEVICEINFO_V40 struDeviceInfoV40 = {0};
struLoginInfo.bUseAsynLogin = false;
struLoginInfo.wPort = 8000;
memcpy(struLoginInfo.sDeviceAddress, "192.168.10.108", NET_DVR_DEV_ADDRESS_MAX_LEN);
memcpy(struLoginInfo.sUserName, "admin", NAME_LEN);
memcpy(struLoginInfo.sPassword, "hmj", NAME_LEN);
lUserID = NET_DVR_Login_V40(&struLoginInfo, &struDeviceInfoV40);
if (lUserID < 0)
{
printf("pyd1---Login error, %d\n", NET_DVR_GetLastError());
return HPR_ERROR;
}
//control
int iChannel = 1;//设备通道号
WORD dwPTZCommand; //转动控制
DWORD dwStop = 1; //开始转动0,停止1
int dwSpeed = 1; //速度为[1,7]
int range = 200;
//ros发布话题消息
setlocale(LC_ALL,"");
ros::NodeHandle nh;
ros::Subscriber sub =nh.subscribe("yolomsg",5,doyolomsg);
ros::Rate rate(5);
while(ros::ok()){
if(update == 1)
{
if(x >= range)
{
dwStop = 0;
dwPTZCommand = PAN_LEFT;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
}
if(x < -range)
{
dwStop = 0;
dwPTZCommand = PAN_RIGHT;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
}
if(y >= range && abs(x) < range)
{
dwStop = 0;
dwPTZCommand = TILT_UP;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
}
if(y < -range && abs(x) < range)
{
dwStop = 0;
dwPTZCommand = TILT_DOWN;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
}
if(abs(x) <= range && abs(y) <= range)
{
dwStop = 1;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
}
}
if(update == 0)
{
dwStop = 1;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
update = 1;
break;
}
ros::spinOnce();
rate.sleep();
}
return HPR_OK;
}
3. 人工控制部分,主要是为了调试,不用每次都登陆到网站上对云台进行复位:
#include "HCNetSDK.h"
#include "manual_control.h"
#include "ros/ros.h"
#include
#include "public.h"
#include
#include
#include
#include // 新增:用于清空输入流
using namespace std;
int iChannel = 1;
WORD dwPTZCommand;
DWORD dwStop = 1;
int dwSpeed = 3;
// 设置非阻塞输入
void setNonBlockingInput() {
struct termios ttystate;
tcgetattr(STDIN_FILENO, &ttystate);
ttystate.c_lflag &= ~(ICANON | ECHO);
ttystate.c_cc[VMIN] = 0;
tcsetattr(STDIN_FILENO, TCSANOW, &ttystate);
fcntl(STDIN_FILENO, F_SETFL, O_NONBLOCK);
}
// 恢复终端默认设置
void resetTerminal() {
struct termios ttystate;
tcgetattr(STDIN_FILENO, &ttystate);
ttystate.c_lflag |= (ICANON | ECHO);
tcsetattr(STDIN_FILENO, TCSANOW, &ttystate);
}
void manual_control() {
NET_DVR_Init();
long lUserID;
NET_DVR_USER_LOGIN_INFO struLoginInfo = {0};
NET_DVR_DEVICEINFO_V40 struDeviceInfoV40 = {0};
struLoginInfo.bUseAsynLogin = false;
struLoginInfo.wPort = 8000;
memcpy(struLoginInfo.sDeviceAddress, "192.168.10.108", NET_DVR_DEV_ADDRESS_MAX_LEN);
memcpy(struLoginInfo.sUserName, "admin", NAME_LEN);
memcpy(struLoginInfo.sPassword, "hmj", NAME_LEN);
lUserID = NET_DVR_Login_V40(&struLoginInfo, &struDeviceInfoV40);
if (lUserID < 0) {
ROS_ERROR("海康设备登录失败!");
return;
}
setNonBlockingInput();
bool exitFlag = false; // 新增退出标志
char input;
bool isMoving = false;
while (ros::ok() && !exitFlag) { // 添加退出条件
ssize_t bytesRead = read(STDIN_FILENO, &input, 1);
if (bytesRead > 0) {
switch (input) {
case 'w':
dwPTZCommand = TILT_UP;
isMoving = true;
break;
case 's':
dwPTZCommand = TILT_DOWN;
isMoving = true;
break;
case 'a':
dwPTZCommand = PAN_LEFT;
isMoving = true;
break;
case 'd':
dwPTZCommand = PAN_RIGHT;
isMoving = true;
break;
case 'q':
exitFlag = true; // 设置退出标志
break;
default:
isMoving = false;
break;
}
} else {
isMoving = false;
}
// 发送控制命令
if (isMoving) {
dwStop = 0;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
} else {
dwStop = 1;
NET_DVR_PTZControlWithSpeed_Other(lUserID, iChannel, dwPTZCommand, dwStop, dwSpeed);
}
usleep(100000); // 100ms延迟
}
// 清理操作
NET_DVR_Logout(lUserID);
NET_DVR_Cleanup();
// 清空输入缓冲区
tcflush(STDIN_FILENO, TCIFLUSH); // 清空终端缓冲区
resetTerminal(); // 恢复终端设置
// 清空C++输入流
cin.clear();
cin.ignore(numeric_limits::max(), '\n');
}
在创建完成这些文件后,输入catkin_make进行编译,不出意外的话应该能过的哈哈哈,然后source devel/setup.bash
通过一下指令就可以启动了:
rosrun yolo_pkg consoleMain
后续可能在云台的控制部分上pid算法。
rtsp推流的方式不太稳定,影响检测,后续可能使用串口通信。