当前位置: 首页 > news >正文

超维空间S2无人机使用说明书——51、基础版——使用yolov8进行目标跟踪

引言:为了提高yolo识别的质量,提高了yolo的版本,改用yolov8进行物体识别,同时系统兼容了低版本的yolo,包括基于C++的yolov3和yolov4,以及yolov7。

简介,为了提高识别速度,系统采用了GPU进行加速,在使用7W功率的情况,大概可以稳定在20FPS,满功率情况下可以适当提高。

硬件:D435摄像头,Jetson orin nano 8G

环境:ubuntu20.04,ros-noetic, yolov8

注:目标跟随是在木根识别的基础上进行,因此本小节和yolov8识别小节类似,只是在此基础上添加了跟随控制程序

步骤一: 启动摄像头,获取摄像头发布的图像话题

roslaunch realsense2_camera rs_camera.launch  

请添加图片描述

没有出现红色报错,出现如下界面,表明摄像头启动成功

请添加图片描述

步骤二:启动yolov8识别节点

roslaunch yolov8_ros yolo_v8.launch 

launch文件如下,参数use_cpu设置为false,因为实际使用GPU加速,不是CPU跑,另外参数pub_topic是yolov8识别到目标后发布出来的物体在镜头中的位置,程序作了修改,直接给出目标物的中心位置,其中参数image_topic是订阅的节点话题,一定要与摄像头发布的实际话题名称对应上。

<?xml version="1.0" encoding="utf-8"?>
<launch><!-- Load Parameter --><param name="use_cpu"           value="false" /><!-- Start yolov8 and ros wrapper --><node pkg="yolov8_ros" type="yolo_v8.py" name="yolov8_ros" output="screen" ><param name="weight_path"       value="$(find yolov8_ros)/weights/yolov8n.pt"/><param name="image_topic"       value="/camera/color/image_raw" /><param name="pub_topic"         value="/object_position" /><param name="camera_frame"      value="camera_color_frame"/><param name="visualize"         value="false"/><param name="conf"              value="0.3" /></node>
</launch>

请添加图片描述

出现如下界面表示yolov8启动成功

请添加图片描述

步骤三:打开rqt工具,查看识别效果

注:步骤三不是必须的,可以跳过直接进行步骤四

rqt_image_view 

请添加图片描述

等待出现如下界面后,选择yolov8/detection_image查看yolov8识别效果

请添加图片描述

步骤四:启动跟随控制程序

(1)、终端启动程序

roslaunch follow_yolov8 follow_yolov8.launch  

请添加图片描述

(2)、launch文件详解

<?xml version="1.0" encoding="utf-8"?>
<launch><param name="target_object_id" value="chair" /><node pkg="follow_yolov8" type="follow_yolov8" name="follow_yolov8" output="screen" />
</launch>

launch文件中加载的参数target_object_id是指定跟随的目标名称,无人机在识别到这个目标以后,会通过全向的速度控制保持目标始终在无人机的视野中。launch文件中指定参数chair,因此在识别chair以后,可以看到终端会打印日志已经识别到指定的目标物

请添加图片描述

请添加图片描述

步骤五:控制部分代码

此处抛砖引玉,仅仅做最简单的速度控制,读者可以根据自己的理解,添加类似PID等控制跟随的算法,本文不再展开

#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/TwistStamped.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
#include <mavros_msgs/PositionTarget.h>
#include <cmath>
#include <tf/transform_listener.h>
#include <nav_msgs/Odometry.h>
#include <mavros_msgs/CommandLong.h>   
#include <yolov8_ros_msgs/BoundingBoxes.h>
#include <string>#define MAX_ERROR 50
#define VEL_SET   0.15
#define ALTITUDE  0.40using namespace std;yolov8_ros_msgs::BoundingBoxes object_pos;
nav_msgs::Odometry local_pos;
mavros_msgs::State current_state;  
mavros_msgs::PositionTarget setpoint_raw;//检测到的物体坐标值
double position_detec_x = 0;
double position_detec_y = 0;
std::string Class = "no_object";std::string target_object_id = "eight";void state_cb(const mavros_msgs::State::ConstPtr& msg);void local_pos_cb(const nav_msgs::Odometry::ConstPtr& msg);void object_pos_cb(const yolov8_ros_msgs::BoundingBoxes::ConstPtr& msg);int main(int argc, char **argv)
{//防止中文输出乱码setlocale(LC_ALL, "");//初始化节点,名称为visual_throwros::init(argc, argv, "follow_yolov8");//创建句柄ros::NodeHandle nh;//订阅无人机状态话题ros::Subscriber state_sub     = nh.subscribe<mavros_msgs::State>("mavros/state", 100, state_cb);//订阅无人机实时位置信息ros::Subscriber local_pos_sub = nh.subscribe<nav_msgs::Odometry>("/mavros/local_position/odom", 100, local_pos_cb);//订阅实时位置信息ros::Subscriber object_pos_sub = nh.subscribe<yolov8_ros_msgs::BoundingBoxes>("object_position", 100, object_pos_cb);//发布无人机位置控制话题ros::Publisher  local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>("mavros/setpoint_position/local", 100);//发布无人机多维控制话题ros::Publisher  mavros_setpoint_pos_pub = nh.advertise<mavros_msgs::PositionTarget>("/mavros/setpoint_raw/local", 100);   //请求无人机解锁服务        ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>("mavros/cmd/arming");//请求无人机设置飞行模式,本代码请求进入offboardros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>("mavros/set_mode");//请求控制舵机客户端ros::ServiceClient ctrl_pwm_client = nh.serviceClient<mavros_msgs::CommandLong>("mavros/cmd/command");//循环频率ros::Rate rate(20.0); ros::param::get("target_object_id", target_object_id);//等待连接到PX4无人机while(ros::ok() && current_state.connected){ros::spinOnce();rate.sleep();}setpoint_raw.type_mask = 1 + 2 + /*4 + 8 + 16 + 32*/ + 64 + 128 + 256 + 512 + 1024 + 2048;setpoint_raw.coordinate_frame = 8;setpoint_raw.position.x = 0;setpoint_raw.position.y = 0;setpoint_raw.position.z = 0 + ALTITUDE;mavros_setpoint_pos_pub.publish(setpoint_raw);for(int i = 100; ros::ok() && i > 0; --i){mavros_setpoint_pos_pub.publish(setpoint_raw);ros::spinOnce();rate.sleep();}//请求offboard模式变量mavros_msgs::SetMode offb_set_mode;offb_set_mode.request.custom_mode = "OFFBOARD";//请求解锁变量mavros_msgs::CommandBool arm_cmd;arm_cmd.request.value = true;ros::Time last_request = ros::Time::now();//请求进入offboard模式并且解锁无人机,15秒后退出,防止重复请求       while(ros::ok()){//请求进入OFFBOARD模式if( current_state.mode != "OFFBOARD" && (ros::Time::now() - last_request > ros::Duration(5.0))){if( set_mode_client.call(offb_set_mode) && offb_set_mode.response.mode_sent){ROS_INFO("Offboard enabled");}last_request = ros::Time::now();}else {//请求解锁if( !current_state.armed && (ros::Time::now() - last_request > ros::Duration(5.0))){if( arming_client.call(arm_cmd) && arm_cmd.response.success){ROS_INFO("Vehicle armed");}last_request = ros::Time::now();}}if(ros::Time::now() - last_request > ros::Duration(5.0))break;mavros_setpoint_pos_pub.publish(setpoint_raw);ros::spinOnce();rate.sleep();} while(ros::ok()){      //此处表示识别到launch文件中指定的目标//if(object_pos.bounding_boxes[0].Class == "chair")if(Class == target_object_id){ROS_INFO("识别到目标,采用速度控制进行跟随");//摄像头向下安装,因此摄像头的Z对应无人机的X前后方向,Y对应Y左右方向//无人机左右移动速度控制if(position_detec_x-320 >= MAX_ERROR){setpoint_raw.velocity.y =  -VEL_SET;}					else if(position_detec_x-320 <= -MAX_ERROR){setpoint_raw.velocity.y =  VEL_SET;}	else{setpoint_raw.velocity.y =  0;}//无人机前后移动速度控制if(position_detec_y-240 >= MAX_ERROR){setpoint_raw.velocity.x =  -VEL_SET;}					else if(position_detec_y-240 <= -MAX_ERROR){setpoint_raw.velocity.x =  VEL_SET;}	else{setpoint_raw.velocity.x =  0;}}else{setpoint_raw.velocity.x =  0;setpoint_raw.velocity.y =  0;}setpoint_raw.type_mask = 1 + 2 +/* 4 + 8 + 16 + 32*/ + 64 + 128 + 256 + 512 /*+ 1024 + 2048*/;setpoint_raw.coordinate_frame = 8;setpoint_raw.velocity.x = 0;setpoint_raw.position.z = 0 + ALTITUDE;setpoint_raw.yaw        = 0;mavros_setpoint_pos_pub.publish(setpoint_raw);ros::spinOnce();rate.sleep();}return 0;
}void state_cb(const mavros_msgs::State::ConstPtr& msg)
{current_state = *msg;
}void local_pos_cb(const nav_msgs::Odometry::ConstPtr& msg)
{local_pos = *msg;
}void object_pos_cb(const yolov8_ros_msgs::BoundingBoxes::ConstPtr& msg)
{object_pos = *msg;position_detec_x = object_pos.bounding_boxes[0].xmin;position_detec_y = object_pos.bounding_boxes[0].ymin;Class =            object_pos.bounding_boxes[0].Class;
}

从图中可以看出,在10W功率的情况下,大概在30帧的效果,识别准确度比较高

相关文章:

超维空间S2无人机使用说明书——51、基础版——使用yolov8进行目标跟踪

引言&#xff1a;为了提高yolo识别的质量&#xff0c;提高了yolo的版本&#xff0c;改用yolov8进行物体识别&#xff0c;同时系统兼容了低版本的yolo&#xff0c;包括基于C的yolov3和yolov4&#xff0c;以及yolov7。 简介&#xff0c;为了提高识别速度&#xff0c;系统采用了G…...

Transformer(seq2seq、self-attention)学习笔记

在self-attention 基础上记录一篇Transformer学习笔记 Transformer的网络结构EncoderDecoder 模型训练与评估 Transformer的网络结构 Transformer是一种seq2seq 模型。输入一个序列&#xff0c;经过encoder、decoder输出结果也是一个序列&#xff0c;输出序列的长度由模型决定…...

2023-12-29 服务器开发-centos部署ftp

摘要: 2023-12-29 服务器开发-centos-部署ftp 部署ftp vsftpd&#xff08;very secure FTP daemon&#xff09;是Linux下的一款小巧轻快、安全易用的FTP服务器软件。本教程介绍如何在Linux实例上安装并配置vsftpd。 前提条件 已创建ECS实例并为实例分配了公网IP地址。 背景…...

螺旋数字阵(100%用例)C卷 (JavaPythonNode.jsC语言C++)

疫情期间,小明隔离在家,百无聊赖,在纸上写数字玩。他发明了一种写法: 给出数字个数n和行数m (0 < n <= 999,0 < m <= 999) ,从左上角的1开始,按照顺时针螺旋向内写方式,依次写出2,3...n,最终形成一个m行矩阵 小明对这个矩阵有些要求 1.每行数字的个数一样多…...

AUTOSAR从入门到精通-网络通信(UDPNm)(二)

目录 前言 原理 UdpNm工作原理 UdpNm与CanNM的区别联系 网络管理算法...

显示器与按键(LCD 1602 + button)

一、实验目的&#xff1a; &#xff08;1&#xff09;学习lcd 1602的编程与使用、 &#xff08;2&#xff09;机械式复位开关button软件消抖的方法。 二、实验内容&#xff1a; 1、必做&#xff1a;先显示开机画面&#xff0c;&#xff1a;在1602显示器上&#xff0c;分两行…...

2020年认证杯SPSSPRO杯数学建模B题(第一阶段)分布式无线广播全过程文档及程序

2020年认证杯SPSSPRO杯数学建模 B题 分布式无线广播 原题再现&#xff1a; 以广播的方式来进行无线网通信&#xff0c;必须解决发送互相冲突的问题。无线网的许多基础通信协议都使用了令牌的方法来解决这个问题&#xff0c;在同一个时间段内&#xff0c;只有唯一一个拿到令牌…...

【CISSP学习笔记】7. 安全评估与测试

该知识领域涉及如下考点&#xff0c;具体内容分布于如下各个子章节&#xff1a; 设计和验证评估、测试和审计策略进行安全控制测试收集安全过程数据&#xff08;例如&#xff0c;技术和管理&#xff09;分析测试输出并生成报告执行或协助安全审计 7.1. 构建安全评估和测试方案…...

Gateway集成方法以及拦截器和过滤器的使用

前提&#xff1a;请先创建好一个SpringBoot项目 1. 引入依赖 SpringCloud 和 alibabaCloud 、 SpringBoot间对版本有强制要求&#xff0c;我使用的springboot是3.0.2的版本。版本对应关系请看&#xff1a;版本说明 alibaba/spring-cloud-alibaba Wiki GitHub <dependency…...

第G2周:人脸图像生成(DCGAN)

&#x1f368; 本文为[&#x1f517;365天深度学习训练营学习记录博客\n&#x1f366; 参考文章&#xff1a;365天深度学习训练营\n&#x1f356; 原作者&#xff1a;[K同学啊 | 接辅导、项目定制]\n&#x1f680; 文章来源&#xff1a;[K同学的学习圈子](https://www.yuque.co…...

【Web】Ctfshow Thinkphp5 非强制路由RCE漏洞

目录 非强制路由RCE漏洞 web579 web604 web605 web606 web607-610 前面审了一些tp3的sql注入,终于到tp5了&#xff0c;要说tp5那最经典的还得是rce 下面介绍非强制路由RCE漏洞 非强制路由RCE漏洞原理 非强制路由相当于开了一个大口子&#xff0c;可以任意调用当前框…...

python3遇到Can‘t connect to HTTPS URL because the SSL module is not available.

远程服务器centos7系统上有minicoda3&#xff0c;觉得太占空间&#xff0c;就把整个文件夹删了&#xff0c;原先的Python3也没了&#xff0c;都要重装。 我自己的步骤&#xff1a;进入管理员模式 1.下载Python3的源码&#xff1a; wget https://www.python.org/ftp/python/3.1…...

QSPI Flash xip取指同时program过程中概率性出现usb播歌时断音

项目场景&#xff1a; USB Audio芯片&#xff0c;代码放到qspi flash中&#xff0c;执行代码时&#xff0c;客户会偶尔保存一些参数&#xff0c;即FPGA验证过程中&#xff0c;每隔10ms向flash info区烧写4个byte&#xff08;取指过程一直存在&#xff0c;且时隙软件不可控&…...

MySQL聚簇索引和非聚簇索引的区别

前言: 聚簇索引和非聚簇索引是数据库中的两种索引类型&#xff0c;他们在组织和存储数据时有不同的方式。 聚簇索引&#xff1a; 简单理解&#xff0c;就是将数据和索引放在了一起&#xff0c;找到了索引也就找到了数据。对于聚簇索引来说&#xff0c;他的非叶子节点上存储的是…...

【C#】蜗牛爬井问题C#控制台实现

文章目录 一、问题描述二、C#控制台代码 一、问题描述 井深30米&#xff0c;蜗牛在井底&#xff0c;每天爬3米又滑下1米&#xff0c;问第几天爬出来 二、C#控制台代码 using System; using System.Collections.Generic; using System.Linq; using System.Text; using System…...

IP地址的四大类型:动态IP、固定IP、实体IP、虚拟IP的区别与应用

在网络通信中&#xff0c;IP地址是设备在互联网上唯一标识的关键元素。动态IP、固定IP、实体IP和虚拟IP是四种不同类型的IP地址&#xff0c;它们各自具有独特的特点和应用场景。 1. 动态IP地址&#xff1a; 动态IP地址是由Internet Service Provider&#xff08;ISP&#xff…...

Linux Debian12安装和使用ImageMagick图像处理工具 常见图片png、jpg格式转webp格式

一、ImageMagick简介 ImageMagick是一套功能强大、稳定而且免费的工具集和开发包。可以用来读、写和图像格式转换&#xff0c;可以处理超过100种图像格式&#xff0c;包括流行的TIFF, JPEG, GIF, PNG, PDF以及PhotoCD等格式。对图片的操作&#xff0c;即可以通过命令行进行&am…...

JavaScript二

目录 流程控制 if判断 while循环 do while for循环 forEach for in Map与set iterator 流程控制 if判断 <script>use strictvar age 5;if(age < 3){alert("haha");}else if(age < 5){alert("hi world");}else{alert("hello wor…...

JavaScript系列——正则表达式

文章目录 需求场景正则表达式的定义创建正则表达式通过 / 表示式/ 创建通过构造函数创建 编写一个正则表达式的模式使用简单模式使用特殊字符常用特殊字符列表特殊字符组和范围 正则表达式使用代码演示 常用示例验证手机号码合法性 小结 需求场景 在前端开发领域&#xff0c;在…...

命令行创建Vue项目

Vue项目创建 1. 打开UI界面 在命令行中&#xff0c;执行如下指令&#xff1a; vue ui 2. 打开项目管理器 3. 创建项目 创建项目的过程&#xff0c;需要联网进行&#xff0c;这可能会耗时比较长的时间&#xff0c;请耐心等待。 windows的命令行&#xff0c;容易卡顿&#xff0c…...

渗透实战PortSwigger靶场-XSS Lab 14:大多数标签和属性被阻止

<script>标签被拦截 我们需要把全部可用的 tag 和 event 进行暴力破解 XSS cheat sheet&#xff1a; https://portswigger.net/web-security/cross-site-scripting/cheat-sheet 通过爆破发现body可以用 再把全部 events 放进去爆破 这些 event 全部可用 <body onres…...

如何为服务器生成TLS证书

TLS&#xff08;Transport Layer Security&#xff09;证书是确保网络通信安全的重要手段&#xff0c;它通过加密技术保护传输的数据不被窃听和篡改。在服务器上配置TLS证书&#xff0c;可以使用户通过HTTPS协议安全地访问您的网站。本文将详细介绍如何在服务器上生成一个TLS证…...

智能分布式爬虫的数据处理流水线优化:基于深度强化学习的数据质量控制

在数字化浪潮席卷全球的今天&#xff0c;数据已成为企业和研究机构的核心资产。智能分布式爬虫作为高效的数据采集工具&#xff0c;在大规模数据获取中发挥着关键作用。然而&#xff0c;传统的数据处理流水线在面对复杂多变的网络环境和海量异构数据时&#xff0c;常出现数据质…...

iOS性能调优实战:借助克魔(KeyMob)与常用工具深度洞察App瓶颈

在日常iOS开发过程中&#xff0c;性能问题往往是最令人头疼的一类Bug。尤其是在App上线前的压测阶段或是处理用户反馈的高发期&#xff0c;开发者往往需要面对卡顿、崩溃、能耗异常、日志混乱等一系列问题。这些问题表面上看似偶发&#xff0c;但背后往往隐藏着系统资源调度不当…...

算法:模拟

1.替换所有的问号 1576. 替换所有的问号 - 力扣&#xff08;LeetCode&#xff09; ​遍历字符串​&#xff1a;通过外层循环逐一检查每个字符。​遇到 ? 时处理​&#xff1a; 内层循环遍历小写字母&#xff08;a 到 z&#xff09;。对每个字母检查是否满足&#xff1a; ​与…...

C++课设:简易日历程序(支持传统节假日 + 二十四节气 + 个人纪念日管理)

名人说:路漫漫其修远兮,吾将上下而求索。—— 屈原《离骚》 创作者:Code_流苏(CSDN)(一个喜欢古诗词和编程的Coder😊) 专栏介绍:《编程项目实战》 目录 一、为什么要开发一个日历程序?1. 深入理解时间算法2. 练习面向对象设计3. 学习数据结构应用二、核心算法深度解析…...

【p2p、分布式,区块链笔记 MESH】Bluetooth蓝牙通信 BLE Mesh协议的拓扑结构 定向转发机制

目录 节点的功能承载层&#xff08;GATT/Adv&#xff09;局限性&#xff1a; 拓扑关系定向转发机制定向转发意义 CG 节点的功能 节点的功能由节点支持的特性和功能决定。所有节点都能够发送和接收网格消息。节点还可以选择支持一个或多个附加功能&#xff0c;如 Configuration …...

数据库正常,但后端收不到数据原因及解决

从代码和日志来看&#xff0c;后端SQL查询确实返回了数据&#xff0c;但最终user对象却为null。这表明查询结果没有正确映射到User对象上。 在前后端分离&#xff0c;并且ai辅助开发的时候&#xff0c;很容易出现前后端变量名不一致情况&#xff0c;还不报错&#xff0c;只是单…...

2025.6.9总结(利与弊)

凡事都有两面性。在大厂上班也不例外。今天找开发定位问题&#xff0c;从一个接口人不断溯源到另一个 接口人。有时候&#xff0c;不知道是谁的责任填。将工作内容分的很细&#xff0c;每个人负责其中的一小块。我清楚的意识到&#xff0c;自己就是个可以随时替换的螺丝钉&…...

Qwen系列之Qwen3解读:最强开源模型的细节拆解

文章目录 1.1分钟快览2.模型架构2.1.Dense模型2.2.MoE模型 3.预训练阶段3.1.数据3.2.训练3.3.评估 4.后训练阶段S1: 长链思维冷启动S2: 推理强化学习S3: 思考模式融合S4: 通用强化学习 5.全家桶中的小模型训练评估评估数据集评估细节评估效果弱智评估和民间Arena 分析展望 如果…...