超维空间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帧的效果,识别准确度比较高

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.xdnf.cn/news/823249.html

如若内容造成侵权/违法违规/事实不符,请联系一条长河网进行投诉反馈,一经查实,立即删除!

相关文章

Vue小练习--任务列表

这是一个非常实用的例子&#xff0c;主要实用的是v-model、v-on、v-for指令&#xff0c;javaScript的数组也会涉及一些&#xff0c;javaScript数组方法有很多&#xff0c;本文使用的添加元素和删除元素非常实用&#xff0c;可以记下来。 设计思路 很多例子看起来很难&#xf…

使用Google OSV工具扫描依赖安全漏洞

安全漏洞是软件工程化能力的试金石 2021年年底&#xff0c;Log4j的漏洞陆续被公开。因为该框架被大量的开源软件依赖&#xff0c;所以&#xff0c;漏洞影响面非常大。 面对这个漏洞&#xff0c;我们遇到的第一个问题是&#xff1a;如何知道我们哪些工程使用了Log4j&#xff1f;…

用python画最简单的图案,用python画小猫简单代码

本篇文章给大家谈谈用python画小猫简单100行代码&#xff0c;以及用python画最简单的图案&#xff0c;希望对各位有所帮助&#xff0c;不要忘了收藏本站喔。 Source code download: 本文相关源码 from turtle import * #两个函数用于画心 defcurvemove():for i in range(200): …

电池充电器、监控器和控制器AD7284WBSWZ、LT8490EUKJ、LTC4162EUFD-FAD、LTC4162IUFD-LAD【电源管理】

1、AD7284WBSWZ 8通道锂离子电池监控系统 IC 64LQFP AD7284 8通道锂离子电池监控系统包括对堆叠式锂离子电池进行通用监控所需的全部功能。AD7284具有支持四到八个电池管理单元的多路复用单元电压和辅助模数转换器 (ADC) 测量通道。设计人员可以使用四个辅助ADC输入通道进行温…

lag-llama源码解读(Lag-Llama: Towards Foundation Models for Time Series Forecasting)

Lag-Llama: Towards Foundation Models for Time Series Forecasting 文章内容&#xff1a; 时间序列预测任务&#xff0c;单变量预测单变量&#xff0c;基于Llama大模型&#xff0c;在zero-shot场景下模型表现优异。创新点&#xff0c;引入滞后特征作为协变量来进行预测。 获得…

Power Apps 学习笔记 - IOrganizationService Interface

文章目录 1. IOrganization Interface1.1 基本介绍1.2 方法分析 2. Entity对象2.1 Constructor2.2 Properties2.3 Methods 3. 相关方法3.1 单行查询 Retrive3.2 多行查询 RetriveMultiple3.3 增加 Create3.4 删除 Delete3.5 修改 Update 1. IOrganization Interface 1.1 基本介…

rax3000m刷openwrt固件

rax3000m刷机过程&#xff08;nand版本&#xff09; 刷机准备文件https://www.123pan.com/s/X5m9-6Ynj.html提取码:VtBW 接线关系&#xff1a;路由器lan口接电脑 1.上传配置开启ssh的配置文件&#xff08;登录路由器后台管理界面在找到配置管理&#xff0c;上传配置文件rax3…

[NCTF 2022] web题解

[NCTF 2022]calc 考点&#xff1a;python环境变量注入 打开题目&#xff0c;F12有hint 访问一下得到源码 app.route("/calc",methods[GET]) def calc():ip request.remote_addrnum request.values.get("num")log "echo {0} {1} {2}> ./tmp/log…

【Unity美术】Unity工程师对3D模型需要达到的了解【一】

&#x1f468;‍&#x1f4bb;个人主页&#xff1a;元宇宙-秩沅 &#x1f468;‍&#x1f4bb; hallo 欢迎 点赞&#x1f44d; 收藏⭐ 留言&#x1f4dd; 加关注✅! &#x1f468;‍&#x1f4bb; 本文由 秩沅 原创 &#x1f468;‍&#x1f4bb; 收录于专栏&#xff1a;Uni…

后端程序员React初接触1

后端程序员React初接触 学习react基础与相关库的使用学习 包括react基础 路由 组件库等等 react是用于构建用户界面的JavaScript库 发送请求获取数据处理数据操作dom呈现页面&#xff08;react帮忙操作dom&#xff09; 数据渲染为视图 有facebook打造并开源 解决的问题 dom操…

集群部署篇--Redis 哨兵模式

文章目录 前言一、哨兵模式介绍&#xff1a;1.1 介绍&#xff1a;1.2 工作机制&#xff1a; 二、哨兵模式搭建&#xff1a;2. 1 redis 主从搭建&#xff1a;2.2 setinel 集群搭建&#xff1a;2.2.1 配置&#xff1a; sentinel.conf &#xff1a;2.2.2 运行容器&#xff1a;2.2.…

jQuery日历签到插件下载

jQuery日历签到插件下载-遇见你与你分享

【MySQL】数据库之存储过程(“SQL语句的脚本“)

目录 一、什么是存储过程&#xff1f; 二、存储过程的作用 三、如何创建、调用、查看、删除、修改存储过程 四、存储过程的参数&#xff08;输入参数&#xff0c;输出参数&#xff0c;输入输出参数&#xff09; 第一种&#xff1a;输入参数 第二种&#xff1a;输出参数 …

Leetcode算法系列| 10. 正则表达式匹配

目录 1.题目2.题解C# 解法一&#xff1a;分段匹配法C# 解法二&#xff1a;回溯法C# 解法三&#xff1a;动态规划 1.题目 给你一个字符串 s 和一个字符规律 p&#xff0c;请你来实现一个支持 ‘.’ 和 ‘*’ 的正则表达式匹配。 1.‘.’ 匹配任意单个字符 2.‘.’ 匹配任意单个字…

【DevOps 工具链】日志管理工具 - 22种 选型(读这一篇就够了)

文章目录 1、简述2、内容分类3、归纳对比表&#xff08;排序不分先后&#xff09;4、日志管理主要目的5、日志管理工具 22种 详细&#xff08;排序不分先后&#xff09;5.1、ManageEngine EventLog Analyzer5.1.1、简介5.1.2、效果图5.1.3、日志管理架构5.1.4、EventLog Analyz…

HarmonyOS 路由传参

本文 我们来说两个page界面间的数据传递 路由跳转 router.pushUrl 之前我们用了不少了 但是我们只用了它的第一个参数 url 其实他还有个params参数 我们第一个组件可以编写代码如下 import router from ohos.router Entry Component struct Index {build() {Row() {Column() …

交互式笔记Jupyter Notebook本地部署并实现公网远程访问内网服务器

最近&#xff0c;我发现了一个超级强大的人工智能学习网站。它以通俗易懂的方式呈现复杂的概念&#xff0c;而且内容风趣幽默。我觉得它对大家可能会有所帮助&#xff0c;所以我在此分享。点击这里跳转到网站。 文章目录 1.前言2.Jupyter Notebook的安装2.1 Jupyter Notebook下…

C编程指针篇----包括历年真题

一&#xff0c;&#xff08;20年&#xff09;用指针字符逆序 代码&#xff1a; int main() {char s[7] "monkey", * p1, * p2, c;p1 p2 s;while (*p2) p2;p2--;while (p2 > p1) {c *p1; *p1 *p2; *p2-- c; }printf("%s", s);return 0; } 运行结…

【华为机试】2023年真题B卷(python)-解密犯罪时间

一、题目 题目描述&#xff1a; 警察在侦破一个案件时&#xff0c;得到了线人给出的可能犯罪时间&#xff0c;形如 “HH:MM” 表示的时刻。 根据警察和线人的约定&#xff0c;为了隐蔽&#xff0c;该时间是修改过的&#xff0c;解密规则为&#xff1a; 利用当前出现过的数字&am…

jdk与cglib动态代理及原理

Spring的AOP在运行时多以jdk及cglib动态代理来实现。&#xff08;作者jdk是1.8版本&#xff09; 1 jdk 动态代理 Java中使用动态代理&#xff0c;只能对接口进行代理&#xff0c;不能对普通类进行代理。主要是由一个类及一个接口来实现&#xff1a; InvocationHandler&#…