超维空间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进行目标跟踪
引言:为了提高yolo识别的质量,提高了yolo的版本,改用yolov8进行物体识别,同时系统兼容了低版本的yolo,包括基于C的yolov3和yolov4,以及yolov7。 简介,为了提高识别速度,系统采用了G…...

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

2023-12-29 服务器开发-centos部署ftp
摘要: 2023-12-29 服务器开发-centos-部署ftp 部署ftp vsftpd(very secure FTP daemon)是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)
一、实验目的: (1)学习lcd 1602的编程与使用、 (2)机械式复位开关button软件消抖的方法。 二、实验内容: 1、必做:先显示开机画面,:在1602显示器上,分两行…...

2020年认证杯SPSSPRO杯数学建模B题(第一阶段)分布式无线广播全过程文档及程序
2020年认证杯SPSSPRO杯数学建模 B题 分布式无线广播 原题再现: 以广播的方式来进行无线网通信,必须解决发送互相冲突的问题。无线网的许多基础通信协议都使用了令牌的方法来解决这个问题,在同一个时间段内,只有唯一一个拿到令牌…...
【CISSP学习笔记】7. 安全评估与测试
该知识领域涉及如下考点,具体内容分布于如下各个子章节: 设计和验证评估、测试和审计策略进行安全控制测试收集安全过程数据(例如,技术和管理)分析测试输出并生成报告执行或协助安全审计 7.1. 构建安全评估和测试方案…...

Gateway集成方法以及拦截器和过滤器的使用
前提:请先创建好一个SpringBoot项目 1. 引入依赖 SpringCloud 和 alibabaCloud 、 SpringBoot间对版本有强制要求,我使用的springboot是3.0.2的版本。版本对应关系请看:版本说明 alibaba/spring-cloud-alibaba Wiki GitHub <dependency…...

第G2周:人脸图像生成(DCGAN)
🍨 本文为[🔗365天深度学习训练营学习记录博客\n🍦 参考文章:365天深度学习训练营\n🍖 原作者:[K同学啊 | 接辅导、项目定制]\n🚀 文章来源:[K同学的学习圈子](https://www.yuque.co…...

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

python3遇到Can‘t connect to HTTPS URL because the SSL module is not available.
远程服务器centos7系统上有minicoda3,觉得太占空间,就把整个文件夹删了,原先的Python3也没了,都要重装。 我自己的步骤:进入管理员模式 1.下载Python3的源码: wget https://www.python.org/ftp/python/3.1…...
QSPI Flash xip取指同时program过程中概率性出现usb播歌时断音
项目场景: USB Audio芯片,代码放到qspi flash中,执行代码时,客户会偶尔保存一些参数,即FPGA验证过程中,每隔10ms向flash info区烧写4个byte(取指过程一直存在,且时隙软件不可控&…...
MySQL聚簇索引和非聚簇索引的区别
前言: 聚簇索引和非聚簇索引是数据库中的两种索引类型,他们在组织和存储数据时有不同的方式。 聚簇索引: 简单理解,就是将数据和索引放在了一起,找到了索引也就找到了数据。对于聚簇索引来说,他的非叶子节点上存储的是…...
【C#】蜗牛爬井问题C#控制台实现
文章目录 一、问题描述二、C#控制台代码 一、问题描述 井深30米,蜗牛在井底,每天爬3米又滑下1米,问第几天爬出来 二、C#控制台代码 using System; using System.Collections.Generic; using System.Linq; using System.Text; using System…...

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

Linux Debian12安装和使用ImageMagick图像处理工具 常见图片png、jpg格式转webp格式
一、ImageMagick简介 ImageMagick是一套功能强大、稳定而且免费的工具集和开发包。可以用来读、写和图像格式转换,可以处理超过100种图像格式,包括流行的TIFF, JPEG, GIF, PNG, PDF以及PhotoCD等格式。对图片的操作,即可以通过命令行进行&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系列——正则表达式
文章目录 需求场景正则表达式的定义创建正则表达式通过 / 表示式/ 创建通过构造函数创建 编写一个正则表达式的模式使用简单模式使用特殊字符常用特殊字符列表特殊字符组和范围 正则表达式使用代码演示 常用示例验证手机号码合法性 小结 需求场景 在前端开发领域,在…...

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

微信小程序之bind和catch
这两个呢,都是绑定事件用的,具体使用有些小区别。 官方文档: 事件冒泡处理不同 bind:绑定的事件会向上冒泡,即触发当前组件的事件后,还会继续触发父组件的相同事件。例如,有一个子视图绑定了b…...

RocketMQ延迟消息机制
两种延迟消息 RocketMQ中提供了两种延迟消息机制 指定固定的延迟级别 通过在Message中设定一个MessageDelayLevel参数,对应18个预设的延迟级别指定时间点的延迟级别 通过在Message中设定一个DeliverTimeMS指定一个Long类型表示的具体时间点。到了时间点后…...
从零实现富文本编辑器#5-编辑器选区模型的状态结构表达
先前我们总结了浏览器选区模型的交互策略,并且实现了基本的选区操作,还调研了自绘选区的实现。那么相对的,我们还需要设计编辑器的选区表达,也可以称为模型选区。编辑器中应用变更时的操作范围,就是以模型选区为基准来…...
css3笔记 (1) 自用
outline: none 用于移除元素获得焦点时默认的轮廓线 broder:0 用于移除边框 font-size:0 用于设置字体不显示 list-style: none 消除<li> 标签默认样式 margin: xx auto 版心居中 width:100% 通栏 vertical-align 作用于行内元素 / 表格单元格ÿ…...
聊一聊接口测试的意义有哪些?
目录 一、隔离性 & 早期测试 二、保障系统集成质量 三、验证业务逻辑的核心层 四、提升测试效率与覆盖度 五、系统稳定性的守护者 六、驱动团队协作与契约管理 七、性能与扩展性的前置评估 八、持续交付的核心支撑 接口测试的意义可以从四个维度展开,首…...
全面解析各类VPN技术:GRE、IPsec、L2TP、SSL与MPLS VPN对比
目录 引言 VPN技术概述 GRE VPN 3.1 GRE封装结构 3.2 GRE的应用场景 GRE over IPsec 4.1 GRE over IPsec封装结构 4.2 为什么使用GRE over IPsec? IPsec VPN 5.1 IPsec传输模式(Transport Mode) 5.2 IPsec隧道模式(Tunne…...
Python 包管理器 uv 介绍
Python 包管理器 uv 全面介绍 uv 是由 Astral(热门工具 Ruff 的开发者)推出的下一代高性能 Python 包管理器和构建工具,用 Rust 编写。它旨在解决传统工具(如 pip、virtualenv、pip-tools)的性能瓶颈,同时…...

FFmpeg:Windows系统小白安装及其使用
一、安装 1.访问官网 Download FFmpeg 2.点击版本目录 3.选择版本点击安装 注意这里选择的是【release buids】,注意左上角标题 例如我安装在目录 F:\FFmpeg 4.解压 5.添加环境变量 把你解压后的bin目录(即exe所在文件夹)加入系统变量…...
作为测试我们应该关注redis哪些方面
1、功能测试 数据结构操作:验证字符串、列表、哈希、集合和有序的基本操作是否正确 持久化:测试aof和aof持久化机制,确保数据在开启后正确恢复。 事务:检查事务的原子性和回滚机制。 发布订阅:确保消息正确传递。 2、性…...
为什么要创建 Vue 实例
核心原因:Vue 需要一个「控制中心」来驱动整个应用 你可以把 Vue 实例想象成你应用的**「大脑」或「引擎」。它负责协调模板、数据、逻辑和行为,将它们变成一个活的、可交互的应用**。没有这个实例,你的代码只是一堆静态的 HTML、JavaScript 变量和函数,无法「活」起来。 …...