超维空间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.hqwc.cn/news/308763.html

如若内容造成侵权/违法违规/事实不符,请联系编程知识网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

数据结构与算法-排序

&#x1f31e;入冬 时寒 添衣 勿病 要开心 排序 &#x1f388;1.排序的基本概念&#x1f388;2.排序的分类&#x1f52d;2.1插入排序&#x1f50e;2.1.1直接插入排序&#x1f50e;2.1.2折半插入排序&#x1f50e;2.1.3希尔排序 &#x1f52d;2.2交换排序&#x1f50e;2.2.1冒泡…

07-项目打包 React Hooks

项目打包 项目打包是为了把整个项目都打包成最纯粹的js&#xff0c;让浏览器可以直接执行 打包命令已经在package.json里面定义好了 运行命令&#xff1a;npm run build&#xff0c;执行时间取决于第三方插件的数量以及电脑配置 打包完之后再build文件夹下&#xff0c;这个…

啊?这也算事务?!

作者简介&#xff1a;大家好&#xff0c;我是smart哥&#xff0c;前中兴通讯、美团架构师&#xff0c;现某互联网公司CTO 联系qq&#xff1a;184480602&#xff0c;加我进群&#xff0c;大家一起学习&#xff0c;一起进步&#xff0c;一起对抗互联网寒冬 学习必须往深处挖&…

Spring Boot学习随笔- 集成MyBatis-Plus,第一个MP程序(环境搭建、@TableName、@TableId、@TableField示例)

学习视频&#xff1a;【编程不良人】Mybatis-Plus整合SpringBoot实战教程,提高的你开发效率,后端人员必备! 引言 MyBatis-Plus是一个基于MyBatis的增强工具&#xff0c;旨在简化开发&#xff0c;提高效率。它扩展了MyBatis的功能&#xff0c;提供了许多实用的特性&#xff0c;…

golang第六卷---go命令

go命令 go/go helpgo versiongo envgo buggo buildgo installgo getgo modgo rungo cleango docgo fixgo fmtgo generatego workgo testgo toolgo vet go/go help 通过该命令&#xff0c;我们可以查看go语言中的所有命令&#xff0c;其中go与go help两个命令是等效的 如下&…

实时数仓应用价值(上)

欢迎关注WX公众号&#xff1a;数据运营入表资产化服务 获取更多算法源码材料 2023数据资源入表白皮书&#xff0c;推荐系统源码下载-CSDN博客 浅析研发支出费用化和资本化的区别-CSDN博客 商业银行数据资产估值白皮书&#xff0c;推荐系统源码下载-CSDN博客 用友BIP数据资…

计算机网络【EPoll原理】

预备知识&#xff1a;内核poll钩子原理 内核函数poll_wait 把当前进程加入到驱动里自定义的等待队列上 &#xff1b; 当驱动事件就绪后&#xff0c;就可以在驱动里自定义的等待队列上唤醒调用poll的进程&#xff1b; 故poll_wait作用&#xff1a;可以让驱动知道事件就绪的时…

笔记1:基于锚框(先验框)的目标检测

一、边缘框&#xff08;bounding box&#xff09; 1.1 定义 边缘框&#xff1a;真实标注的物体位置 2.1 表示方式 1、&#xff08;x1,y1)和(x2,y2) 2、&#xff08;x1,y1)和w,h 二、锚框(anchor box)/先验框&#xff08;prior bounding box&#xff09; 2.1 定义 对边缘…

DDC和PLC的区别

前言 PLC与DDC控制器的比较&#xff0c;一直以来在相关领域内受到广泛关注。每个人站在不同的角度分析&#xff0c;都会有不同的结论&#xff0c;我们今天聊聊这个话题。 基本定义和功能 可编程控制器PLC与直接数字控制器DDC&#xff0c;两者都由CPU模块、I/O模块、显示模块…

Python 内置高阶函数练习(Leetcode500.键盘行)

Python 内置高阶函数练习&#xff08;Leetcode500.键盘行&#xff09; 【一】试题 &#xff08;1&#xff09;地址&#xff1a; 500. 键盘行 - 力扣&#xff08;LeetCode&#xff09; &#xff08;2&#xff09;题目 给你一个字符串数组 words &#xff0c;只返回可以使用在…

可移动磁盘上的文件删除了怎么恢复?详细教程介绍

在我们的日常生活和工作中&#xff0c;可移动磁盘作为一种便携式的存储设备&#xff0c;经常被用来备份和传输数据。然而&#xff0c;有时候由于误操作或不小心的删除&#xff0c;导致可移动磁盘上的文件丢失。这些文件可能包含重要的工作资料、个人照片、视频等&#xff0c;一…

小天使的生命之源:新生儿补充铁剂的细致关怀与注意事项

引言&#xff1a; 新生儿是生命的奇迹&#xff0c;而良好的营养对于他们的健康成长尤为关键。铁是新生儿生命早期阶段发育所必需的重要元素之一&#xff0c;然而&#xff0c;在补充铁剂时&#xff0c;家长需要特别注意一系列细节。本文将深入探讨铁的作用、补充时机&#xff0…