超维空间S2无人机使用说明书——52、初级版——使用PID算法进行基于yolo的目标跟踪

news2025/4/6 6:28:11

引言:在实际工程项目中,为了提高系统的响应速度和稳定性,往往需要采用一定的控制算法进行目标跟踪。这里抛砖引玉,仅采用简单的PID算法进行目标的跟随控制,目标的识别依然采用yolo。对系统要求更高的,可以对算法进行改进,也欢迎读者与我们联系,合作开发。

步骤一:打开摄像头

注意:为了获取目标物的三维位置信息,我们采用了D435深度摄像头,仅供参考,可根据需要自行选择即可

roslaunch realsense2_camera rs_camera.launch

请添加图片描述

查看话题,需要/camera/color/image_raw和/camera/depth/image_rect_raw

请添加图片描述

步骤二:打开yolo识别节点,具体yolo版本可以根据需要选择

 roslaunch darknet_ros darknet_ros.launch 

请添加图片描述

没有报错的情况下,会弹出识别效果图,如下:

请添加图片描述## 注:我这里训练的是自己打印的H型地标,具体可以根据需要选择合适的目标物

步骤三:打开三维坐标转换节点

该节点可以直接一话题的形式输出目标物的名称和真实的位置信息

roslaunch darknet_real_position darknet_real_position.launch

请添加图片描述

launch文件解析

此处的launch文件,以参数的方式指定了识别目标。比如landing,因此这个节点只会把指定的landing地标位置信息打印出来,其他的目标通通忽略

请添加图片描述

查看话题数据/object_position

请添加图片描述

请添加图片描述

从上述图片可以看出,系统非常准确的给出了目标物的名称和真实的位置信息,单位是米。需要指出的是,这里的位置是相对于D435摄像头的位置信息,X表示横向位置,Y表示纵向位置,Z表示实际的距离信息

步骤四:启动PID跟随节点。注意,可以先不要启动mavros,仅仅测试PID控制器发布出的速度是否正确。在确认了没问题后在启动mavros节点,无人机就可以进行正常的跟随运动了

roslaunch follow_pid follow_pid.launch 

请添加图片描述

launch文件解析

这里仅仅进行偏航角度和距离的控制,如果需要对高度方向控制。可以直接复制代码进行简单的修改即可。参数linear_x_p和linear_x_d是距离的PID控制,同理yaw_rate_p和yaw_rate_d是角度的控制。参数target_x_angle是期望保持的角度,通常设置为0即可。最后参数target_distance是期望保持的距离,单位是毫米

请添加图片描述

代码如下:

#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 <string>

#define MAX_ERROR 0.20
#define VEL_SET   0.10
#define ALTITUDE  0.40

using namespace std;


float target_x_angle = 0;
float target_distance = 2000;
float linear_x_p = 0.5;
float linear_x_d = 0.33;
float yaw_rate_p = 4.0;
float yaw_rate_d = 15;

geometry_msgs::PointStamped object_pos; 
nav_msgs::Odometry local_pos;
mavros_msgs::State current_state;  
mavros_msgs::PositionTarget setpoint_raw;
//检测到的物体坐标值
string current_frame_id   = "no_object";
double current_position_x = 0;
double current_position_y = 0;
double current_distance   = 0;

//1、订阅无人机状态话题
ros::Subscriber state_sub;

//2、订阅无人机实时位置信息
ros::Subscriber local_pos_sub;

//3、订阅实时位置信息
ros::Subscriber object_pos_sub;

//4、发布无人机多维控制话题
ros::Publisher  mavros_setpoint_pos_pub;

//5、请求无人机解锁服务        
ros::ServiceClient arming_client;

//6、请求无人机设置飞行模式,本代码请求进入offboard
ros::ServiceClient set_mode_client;

void pid_control()
{
		static float last_error_x_angle = 0;
		static float last_error_distance = 0;				
		float x_angle;
		float distance;

		if(current_position_x == 0 && current_position_y == 0 && current_distance == 0)
		{
			x_angle  = target_x_angle;
			distance = target_distance;
		}
		else
		{
			x_angle = current_position_x / current_distance;
			distance = current_distance;
		}
		
		float error_x_angle = x_angle - target_x_angle;
		float error_distance = distance - target_distance;
		if(error_x_angle > -0.01 && error_x_angle < 0.01)  
		{
			error_x_angle = 0;
		}
		if(error_distance > -80 && error_distance < 80) 
		{
			error_distance = 0;
		}

		setpoint_raw.velocity.x = error_distance*linear_x_p/1000 + (error_distance - last_error_distance)*linear_x_d/1000;
		if(setpoint_raw.velocity.x < -0.3)  
		{
			setpoint_raw.velocity.x = -0.3;
		}
		else if(setpoint_raw.velocity.x > 0.3) 
		{
			setpoint_raw.velocity.x = 0.3;	
		}
		
		setpoint_raw.yaw_rate = error_x_angle*yaw_rate_p + (error_x_angle - last_error_x_angle)*yaw_rate_d;
		if(setpoint_raw.yaw_rate < -0.5)  
		{
			setpoint_raw.yaw_rate = -0.5;
		}
		else if(setpoint_raw.yaw_rate > 0.5) 
		{
			setpoint_raw.yaw_rate = 0.5;
		}
		mavros_setpoint_pos_pub.publish(setpoint_raw);
		last_error_x_angle  = error_x_angle;
		last_error_distance = error_distance;
}

 
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 geometry_msgs::PointStamped::ConstPtr& msg)
{
	object_pos = *msg;
	current_position_x = object_pos.point.x*(-1000);
    current_position_y = object_pos.point.y*(-1000);
    
    //此处将距离由单位米改称毫米,方便提高控制精度
	current_distance   = object_pos.point.z*1000;
	current_frame_id   = object_pos.header.frame_id; 
	pid_control();	 
	//ROS_INFO("current_position_x = %f",current_position_x);
	//ROS_INFO("current_position_y = %f",current_position_y);
	//ROS_INFO("current_distance = %f"  ,current_distance);
}


int main(int argc, char *argv[])
{

    ros::init(argc, argv, "follow_pid");
    
    ros::NodeHandle nh;

	state_sub     = nh.subscribe<mavros_msgs::State>("mavros/state", 100, state_cb);
		
    local_pos_sub = nh.subscribe<nav_msgs::Odometry>("/mavros/local_position/odom", 100, local_pos_cb);
    
    object_pos_sub = nh.subscribe<geometry_msgs::PointStamped>("object_position", 100, object_pos_cb);
		
    mavros_setpoint_pos_pub = nh.advertise<mavros_msgs::PositionTarget>("/mavros/setpoint_raw/local", 100);   
		               
	arming_client = nh.serviceClient<mavros_msgs::CommandBool>("mavros/cmd/arming");
		
	set_mode_client = nh.serviceClient<mavros_msgs::SetMode>("mavros/set_mode");

    ros::Rate rate(20.0); 

	ros::param::get("linear_x_p",linear_x_p);
	ros::param::get("linear_x_d",linear_x_d);
	ros::param::get("yaw_rate_p",yaw_rate_p);
	ros::param::get("yaw_rate_d",yaw_rate_d);
	
	ros::param::get("target_x_angle", target_x_angle);
	ros::param::get("target_distance",target_distance);


	 //等待连接到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 = 1;
	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(15.0))
	    	break;
		mavros_setpoint_pos_pub.publish(setpoint_raw);
        ros::spinOnce();
        rate.sleep();
    }*/   
	
	while(ros::ok())
	{

		//ROS_INFO("11111");
		ros::spinOnce();
		rate.sleep();

	}

}

步骤五:在上述基础上再打开mavros,即可开始跟随控制。代码后续会在B站进行讲解。同时会提供相应的实机演示。链接会在后续给出。

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

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

相关文章

普中STM32-PZ6806L开发板(HAL库函数实现-USART2 中断接收)

简介 实现USART2 的 中断接收&#xff0c; 发送数据。电路原理图 USART2接线 原理图USART2 在主芯片引脚 实物图 其他知识 APIs stm32f1xx_hal_uart.h /* 堵塞发送, pData是发送数据, Size发送数据大小, Timeout是超时时间 */ HAL_StatusTypeDef HAL_UART_Transmit(UAR…

集合基础知识点

集合基础 1. 集合的由来 当 Java 程序中需要存放数据的时候&#xff0c;通常会定义变量来实现数据的存储&#xff0c;但是&#xff0c;当需要存储大量数据的时候该怎么办呢&#xff1f;这时首先想到的是数组&#xff0c;但是&#xff01;数组只能存放同一类型的数据&#xff…

react+redux+antd-mobile 之 记账本案例

1.环境搭建 //使用CRA创建项目&#xff0c;并安装必要依赖&#xff0c;包括下列基础包 //1. Redux状态管理 - reduxjs/toolkit 、 react-redux //2. 路由 - react-router-dom //3. 时间处理 - dayjs //4. class类名处理 - classnames //5. 移动端组件库 - antd-mobile //6. 请…

宝塔部署flask添加ssl即https

在宝塔部署flask的步骤我已经写了一篇博客:宝塔部署flask项目-CSDN博客 之前说如果出现找不到application错误: spawned uWSGI http 1 (pid: 3116) --- no python application found, check your startup logs for errors --- [pid: 3114|app: -1|req: -1/1] 127.0.0.1 () {6…

DockerCompose - 容器编排、模板命令、compose命令、Pottainer 可视化界面管理(一文通关)

目录 一、DockerCompose 容器编排 1.1、简介 1.2、Docker-Compose 安装 1.2.1、在线安装 1.2.2、离线安装 1.3、docker-compose.yml 中的模板命令 前置说明 模板命令 1.4、DockerCompse 命令 前置说明 up down exec ps restart rm top pause暂停 和 unpause恢…

【unity中使用高度图创建地图】

unity中使用高度图创建地图 插件 讲解案例为unity2022版本 这个是插件地址 也可以在资源商店中搜索 terrain-tools 介绍 Terrain Tools入门Terrain Tools是一个软件包&#xff0c;你可以选择将其添加到Unity 2019.1或更高版本中的任何项目中。要将该软件包添加到你的项目…

python+django校园篮球论坛交流系统v5re9

本课题使用Python语言进行开发。基于web,代码层面的操作主要在PyCharm中进行&#xff0c;将系统所使用到的表以及数据存储到MySQL数据库中 技术栈 系统权限按管理员和用户这两类涉及用户划分。 (a) 管理员&#xff1b;管理员使用本系统涉到的功能主要有&#xff1a;首页、个人中…

dash 中的模式匹配回调函数Pattern-Matching Callbacks 8

模式匹配 模式匹配回调选择器 MATCH、ALL 和 ALLSMALLER 允许您编写可以响应或更新任意或动态数量组件的回调函数。 此示例呈现任意数量的 dcc. Dropdown 元素&#xff0c;并且只要任何 dcc. Dropdown 元素发生更改&#xff0c;就会触发回调。尝试添加几个下拉菜单并选择它们的…

56.网游逆向分析与插件开发-游戏增加自动化助手接口-通过UI分析自动药水设定功能

内容来源于&#xff1a;易道云信息技术研究院VIP课 上一节内容&#xff1a;自动药水设定功能的逆向分析-CSDN博客 这次是假设没有之前的思路积累的话&#xff0c;怎样去找按钮事件。 通过ui当做切入点去做&#xff0c;就是一个窗口它显示不显示&#xff0c;游戏怎样控制这个…

【owt-server】一些构建项目梳理

【owt-server】清理日志&#xff1a;owt、srs、ffmpeg 【owt】p2p client mfc 工程梳理【m98】webrtc vs2017构建带符号的debug库【OWT】梳理构建的webrtc和owt mfc工程 m79的mfc客户端及owt-client

【PyQt】(自定义类)QIcon派生,更易用的纯色Icon

嫌Qt自带的icon太丑&#xff0c;自己写了一个&#xff0c;主要用于纯色图标的自由改色。 当然&#xff0c;图标素材得网上找。 Qt原生图标与现代图标对比&#xff1a; 没有对比就没有伤害 Qt图标 网络素材图标 自定义类XJQ_Icon&#xff1a; from PyQt5.QtGui import QIc…

数字PID算法基础

数字PID是由编程语言实现的PID算法并烧录到控制芯片中&#xff0c;控制芯片与电机驱动连接&#xff0c;将PID控制算法的输出转换为PWM控制信号发送给电机驱动电路&#xff0c;电机驱动电路与直流电机相连并将PWM控制信号转换为具有相同占空比的PWM供电电压&#xff0c;通过对输…

MacBook查看本机IP

嘚吧嘚 其实这也不是什么困难的问题&#xff0c;但是今年刚刚入坑Mac&#xff0c;外加用的频率不是很高&#xff0c;每次使用的时候都查&#xff0c;用完就忘&#xff0c;下次用的时候再查&#x1f92e;。真的把自己恶心坏了&#x1f648;。 所以写篇文章记录一下&#x1f92…

Linux:apache优化(4)—— 隐藏版本号

运行环境 yum -y install apr apr-devel cyrus-sasl-devel expat-devel libdb-devel openldap-devel apr-util-devel apr-util pcre-devel pcre gcc make zlib-devel 源码包配置 ./configure --prefix/usr/local/httpd --enable-cgi --enable-rewrite --enable-so --enabl…

MySQL数据库的安装与环境配置

下载 下载MySQL8 安装 解压 配置MySQL环境变量 系统环境变量path D:\ProgramFiles\mysql-8.0.20-winx64\bin 1.点击属性 2.点击高级系统设置 3.点击环境变量 4.在系统变量中找到path 注意这里不是用户变量 5.新建后输入解压的地址 MySQL初始化和启动 以管理员身份运行cmd…

macos下转换.dmg文件为 .iso .cdr文件的简单方法

为了让镜像文件在mac 和windows平台通用, 所以需要将.dmg格式的镜像文件转换为.iso文件, 转换方法也非常简单, 一行命令即可 hdiutil convert /path/to/example.dmg -format UDTO -o /path/to/example.iso 转换完成后的文件名称默认是 example.iso.cdr 这里直接将.cdr后缀删…

Efficient Classification of Very Large Images with Tiny Objects(CVPR2022补1)

文章目录 Two-stage Hierarchical Attention SamplingOne-stageTwo-Stage内存需求 Efficient Contrastive Learning with Attention Sampling Two-stage Hierarchical Attention Sampling 一阶段缩放是hw&#xff0c;提取的特征是h1w1&#xff0c; 二阶段缩放是uv&#xff08;…

Vue中的默认插槽详解

Vue中的默认插槽详解 在 Vue 中&#xff0c;插槽&#xff08;Slot&#xff09;是一种非常强大且灵活的机制&#xff0c;用于在组件中插入内容。Vue 提供了两种类型的插槽&#xff1a;默认插槽&#xff08;Default Slot&#xff09;和具名插槽&#xff08;Named Slot&#xff09…

24、Web攻防-通用漏洞SQL注入MYSQL跨库ACCESS偏移

文章目录 一、SQL注入原理   脚本代码在与数据库进行数据通讯时&#xff08;从数据库取出相关数据进行页面显示&#xff09;&#xff0c;使用预定义的SQL查询语句进行数据查询。能通过参数传递自定义值来实现SQL语句的控制&#xff0c;执行恶意的查询操作&#xff0c;例如查询…

[Angular] 笔记 20:NgContent

chatgpt: 在Angular中&#xff0c;NgContent是用于内容投影&#xff08;Content Projection&#xff09;的一个重要概念。它允许你在一个组件中插入内容&#xff0c;并将这些内容投影到另一个组件中。 当你在一个组件中使用<ng-content></ng-content>标签时&…