赞
踩
本文主要通过yolov8识别对象信息,并通过ros的话题通信回传识别结果与目标坐标,最终通过控制摄像头的舵机转动,让目标对象保持在图像中央。
float64 x
float64 y
float64 w
float64 h
int64 id
#int64 num
float64 probability
F1[] object
int16 num
详细内容见:ROS自定义嵌套数组消息,实现多对象数据传输http://t.csdnimg.cn/bOon4
代码如下(示例):
#!/usr/bin/env python import cv2 from ultralytics import YOLO import numpy as np import rospy from communication_yolo.msg import F1 from communication_yolo.msg import F2 from std_msgs.msg import String rospy.init_node("yolo_ros_pub") #初始化Ros节点 pub = rospy.Publisher("yolom",F2,queue_size=100) #创建发布对象,指定发布方的话题和消息类型 model = YOLO("/home/xj/yolov8_ws/src/communication_yolo/yolov8_main/yolov8n.pt") #加载yolo的模型权重 # model.predict(source=0,imgsz=(384,640),show=True) # model.predict(source=0,show=True) # results = model.track(source=0, imgsz=(384,640),show=True, tracker="bytetrack.yaml") results = model.track(source="rtsp://192.168.144.108:554/stream=0",show=True,stream=True,conf=0.4) for i in results: #print(i.boxes.xyxy) msg_id=i.boxes.id msg_ori=i.boxes.xywhn msg_ori=msg_ori.to('cuda') msg_data=msg_ori.cpu().numpy() #msg_data=msg_ori.boxes.xyxy.numpy() msg=msg_data.tolist() msg=np.array(msg,dtype=np.float64) print(msg) #print(type(msg)) n=len(msg) print("***********************************") print(i.boxes.cls) id=0 while id < n: if i.boxes.cls[id]==0: print("NO.",id," is people") id+=1 print("***********************************") #print(n) j=0 msg_pub=F1() msg_pub2=F2() msg_pub2.num=0 while j < n: if i.boxes.cls[j]==0: print("NO.",j," is people") msg_pub.x=(msg[j][0]) msg_pub.y=(msg[j][1]) msg_pub.w=(msg[j][2]) msg_pub.h=(msg[j][3]) msg_pub.id=j msg_pub2.num +=1 msg_pub2.object.append(msg_pub) print(msg_pub2) #print(msg_pub) #print(type(msg_pub)) j=j+1 pub.publish(msg_pub2) if cv2.waitKey(1) & 0xFF == ord("q"): break #pub.publish(i.boxes.xyxy) rospy.spin()
头文件head.h:
#ifndef _HEAD_H #define _HEAD_H namespace Machine_ns { class Machine { public: void GimbalMove(unsigned char yawSpeed, unsigned char pitchSpeed) ;//水平速度;纵向速度 void GimbalReturnHome(void) ;//回正 void GimbalStop(void) ;//停止运动 }; } #endif
源文件func.cpp:
#include <stdio.h> #include <string.h> #include <sys/socket.h> #include <netinet/in.h> #include <arpa/inet.h> #include <unistd.h> #include<string> #include "/home/xj/yolo_ws/src/communication_yolo/include/communication_yolo/head.h" #include "ros/ros.h" // 目标服务器的IP和端口 #define SERVER_IP "xxxx" #define SERVER_PORT XXX namespace Machine_ns{ //云台速度控制 void Machine::GimbalMove(unsigned char yawSpeed, unsigned char pitchSpeed) { } //云台回中 void Machine::GimbalReturnHome(void) { } //云台停止 void Machine::GimbalStop(void) { } }
cmakeList配置文件
include_directories( include ${catkin_INCLUDE_DIRS} ) ## 声明C++库 add_library(head include/test_head_src/head.h src/func.cpp ) add_dependencies(head ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(head ${catkin_LIBRARIES} )
#include "ros/ros.h" #include <stdio.h> #include <string.h> #include "/home/xj/yolo_ws/devel/include/communication_yolo/F2.h" #include "/home/xj/yolo_ws/src/communication_yolo/include/communication_yolo/head.h" using namespace std; Machine_ns::Machine machine; void doyolomsg(const communication_yolo::F2::ConstPtr& F2) { //int size=sizeof(F2->num); int num=F2->num; ROS_INFO("***********************************"); if (num!=0|num!=NULL) { for(int i=0;i<num;i++) { ROS_INFO("目标%d的坐标信息x为:%f,坐标信息y为:%f,坐标信息w为:%f,坐标信息h为:%f",i,F2->object[i].x,F2->object[i].y,F2->object[i].w,F2->object[i].h); } } ROS_INFO("------------------GimbalStop-------------"); machine.GimbalStop(); ROS_INFO("------------------GimbalStop2-------------"); if (num!=0|num!=NULL) { if (F2->object[0].x!=NULL & F2->object[0].y != NULL) { ROS_INFO("------------------Machinw-------------"); if(F2->object[0].x<0.4)//SP zuo,DJ you { machine.GimbalMove(15,0); } else if(F2->object[0].y<0.4)//SP xia,DJ xia { machine.GimbalMove(0,-15); } else if(F2->object[0].x>0.6)//SP you ,DJ zuo { machine.GimbalMove(-15,0); } else if(F2->object[0].y>0.6)//SP shang,DJ shang { machine.GimbalMove(0,15); } else machine.GimbalStop(); } } else { machine.GimbalStop(); ROS_INFO("------------------GimbalStop3-------------"); } } int main(int argc, char *argv[]) { setlocale(LC_ALL,""); ros::init(argc,argv,"yolo_ros_sub"); ros::NodeHandle nh; std::cout << "Press Enter to continue..."; std::cin.get(); machine.GimbalReturnHome(); std::cout << "start..."; std::cin.get(); ros::Subscriber sub =nh.subscribe("yolom",1000,doyolomsg); ros::spin(); }
#include “/home/xj/yolo_ws/devel/include/communication_yolo/F2.h”
这里是调用自定义数据类型F2
#include “/home/xj/yolo_ws/src/communication_yolo/include/communication_yolo/head.h”
这里是通过头文件调用了摄像头吊舱的控制代码
上图为发布方(识别方)的消息展示,在识别时会将所有识别对象的坐标信息进行发送;下图为接收方的消息展示,发布方只会发布识别对象为“人”的坐标信息给接收方,并在接收方展示。
接收方接收到识别对象为“人”的坐标信息后,如果有多个对象,会跟踪回传的第一个“人”对象,将其识别框的中心点跟踪到画面正中心。
本文主要是通过ROS通信,同时调用yolo和吊舱,并通过头文件和源文件进行吊舱控制,也利用了自定义消息优化了消息格式,是一次不错的实践经历,欢迎各位交流讨论。
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。