超维空间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.40

using 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_throw
    ros::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");
		
	//请求无人机设置飞行模式,本代码请求进入offboard
	ros::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.mfbz.cn/a/267817.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

14章总结

一.lambda表达式 1.lambda表达式简介 lambda表达式不能独立执行&#xff0c;因此必须实现函数式接口&#xff0c;并且会返回一个函数式接口的对象。 语法&#xff1a; ()->结果表达式 参数->结果表达式 (参数1&#xff0c;参数2&#xff0c;...&#xff0c;参数n)->…

老鹰目标检测数据集VOC格式60张

老鹰是天空中的王者&#xff0c;它们拥有极佳的飞行能力。它们能以惊人的速度在天空中翱翔&#xff0c;尤其擅长高空俯冲捕食。老鹰的视力非常敏锐&#xff0c;能够准确地发现地面上的猎物&#xff0c;并迅速下落抓取。它们的爪子强而有力&#xff0c;足以击倒比自己体型庞大的…

顶级旗舰ET9出道,蔚来还是那个「最不计成本」的中国车品牌

作者 |张祥威 编辑 |德新 2008年&#xff0c;李斌和新浪的曹国伟几人一起喝酒&#xff0c;发了第一条微博&#xff0c;「天冷带围巾&#xff0c;心冷发微博」&#xff0c;一晚上涨了2000多个粉丝&#xff0c;他偶尔还会针砭时事&#xff0c;很快积累了最早一波粉丝。 创立蔚来…

各种边缘检测算子的比较研究

边缘检测算子比较研究 文章目录 边缘检测算子比较研究一、引言1.1 边缘检测的重要性1.2 研究背景与意义1.3 研究目的和论文结构 二、文献综述2.1 边缘检测概述2.2 Roberts、Prewitt、Sobel、Laplacian 和 Canny 算子的理论基础和历史2.2.1 **Roberts算子&#xff1a;**2.2.2 **…

全部没有问题 (一.5)

java mooc练习 基础练习&#xff1a; 进阶练习&#xff1a; final 赋值一次 局部 必须赋值 抽象类 多态测试 package com.book;public class moocDraft1 {static int variable1;public void fatherMethod(moocDraft1 a){System.out.println(variable);}public static void…

leetcode——背包问题汇总

本章来汇总一下leetcode中做过的背包问题&#xff0c;包括0-1背包和完全背包。 背包问题的通常形式为&#xff1a;有N件物品和一个最多能背重量为W 的背包。第i件物品的重量是weight[i]&#xff0c;得到的价值是value[i] 。求解将哪些物品装入背包里物品价值总和最大。0-1背包和…

1981-2020年全国各省银行金融机构分布数据、银行金融机构数据

1981-2020年全国各省银行金融机构分布数据/银行金融机构数据 1、时间&#xff1a;1981-2020年 2、指标&#xff1a;统计年度、地区代码、地区名称、金融机构分类代码、金融机构分类名称、营业网点机构个数、营业网点就业人数、营业网点资产总额、法人机构数目、每万人拥有的网…

嵌入式软件工程师常用的

最近我换工作了&#xff0c;看见不同嵌入式软件工程师用的平台都不一样&#xff0c;所以我整理了一下。 PlatformIO: 多平台支持&#xff1a; PlatformIO支持多种嵌入式平台&#xff0c;包括Arduino、ESP8266、ESP32、STM32等&#xff0c;通过一致的开发接口实现平台无关性。 内…

使用ClickHouse UDF与OpenAI模型集成

本文字数&#xff1a;14683&#xff1b;估计阅读时间&#xff1a;37 分钟 作者&#xff1a;Dale McDiarmid 审校&#xff1a;庄晓东&#xff08;魏庄&#xff09; 本文在公众号【ClickHouseInc】首发 Meetup活动 ClickHouse Shenzhen User Group第1届 Meetup 火热报名中&#x…

计算机提示找不到vcruntime140.dll,无法继续执行代码怎么办?如何修复

“找不到vcruntime140.dll&#xff0c;无法继续执行代码”。这个问题可能会让你感到困惑&#xff0c;不知道如何解决。那么&#xff0c;vcruntime140.dll是什么文件&#xff1f;它为什么会丢失&#xff1f;又该如何解决这个问题呢&#xff1f;本文将为你详细介绍vcruntime140.d…

教师未来前景发展

教师是一个光荣而重要的职业&#xff0c;他们承担着培养下一代的责任和使命。随着社会的不断发展和变化&#xff0c;教师的前景也在不断扩大和改变。本文将探讨教师未来的前景发展&#xff0c;并提供一些思考和建议。 首先&#xff0c;教师的就业前景将继续扩大。随着人口的增长…

自定义Springboot项目启动横幅⭐️ 附平平淡淡的周末日常

2023/12/24 天气晴 温度适宜 一觉睡到九点半&#xff0c;谁是神仙&#xff0c;我是神仙日常三联&#xff0c;喂鸡&#xff0c;刷博&#xff0c;肝任务今阳光甚好&#xff0c;遂寻吾之莆田&#xff0c;翻其面&#xff0c;光得以入之&#xff0c;余卧炕&#xff0…

单片机原理及应用

一、任务说明 1.主要任务 本实践环节“51单片机商用电子计价秤设计”要求收集市场电子秤的应用场景的功能列表&#xff0c;给出本系统各功能的参数范围&#xff0c;分析质量检测功能的实现方法&#xff0c;设计单片机仿真系统并通过Proteus进行测试&#xff0c;电子秤是利用物…

注意:国内发生多起Oracle 勒索病毒!

摘要&#xff1a;近期&#xff0c;国内发生多起针对Oracle 数据库的勒索病毒案例&#xff0c;通过分析&#xff0c;该勒索病毒通过网络流传的“PL/SQLDeveloper破解版”进行传播。 1.病毒发起的原因及问题现象 近期&#xff0c;国内发生多起针对Oracle 数据库的勒索病毒案例&…

池化层(pooling)

目录 一、池化层 1、最大池化层 2、平均池化层 3、总结 二、代码实现 1、最大池化与平均池化 2、填充和步幅(padding和strides) 3、多个通道 4、总结 一、池化层 1、最大池化层 2、平均池化层 3、总结 池化层返回窗口中最大或平均值环节卷积层对位置的敏感性同样有窗口…

每日一题——LeetCode888

方法一 个人方法&#xff1a; 交换后要达到相同的数量&#xff0c;那么意味着这个相同的数量就是两个人总数的平均值&#xff0c;假设A总共有4个&#xff0c;B总共有8个&#xff0c;那么最后两个人都要达到6个&#xff0c;如果A的第一盒糖果只有1个&#xff0c;那么B就要给出6…

祝福各位CSDN的小伙伴圣诞快乐

1.源码 <!DOCTYPE html> <html lang"en"><head><meta charset"UTF-8"><title>圣诞树&#x1f384;</title><link rel"stylesheet" href"https://cdnjs.cloudflare.com/ajax/libs/normalize/5.0.0/n…

分布式事务2PC二阶段提交详解

文章目录 概述和概念执行过程和工作流程特点优劣势应用场景总结demo代码样例 概述和概念 二阶段提交&#xff08;2PC&#xff09;是一种用于确保在分布式系统中的所有节点在进行事务提交时保持一致性的算法 二阶段提交&#xff08;Two-Phase Commit&#xff0c;2PC&#xff09…

身为Java“搬砖”程序员,你掌握了多线程吗?

摘要&#xff1a;互联网的每一个角落&#xff0c;无论是大型电商平台的秒杀活动&#xff0c;社交平台的实时消息推送&#xff0c;还是在线视频平台的流量洪峰&#xff0c;背后都离不开多线程技术的支持。在数字化转型的过程中&#xff0c;高并发、高性能是衡量系统性能的核心指…

做到这两条,破解35岁中年危机

最近我在看吴军老师的《富足》这本书&#xff0c;其中有一篇文章讲的是如何破解35岁中年危机&#xff0c;我觉得讲清楚了这个问题的本质&#xff0c;我在这里分享给你&#xff0c;以下内容大部分摘抄自《破解35岁中年危机》一章。 35岁中年危机的原因 35岁中年危机的说法好像…
最新文章