当前位置: 首页 > news >正文

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

引言:在实际工程项目中,为了提高系统的响应速度和稳定性,往往需要采用一定的控制算法进行目标跟踪。这里抛砖引玉,仅采用简单的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.40using 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站进行讲解。同时会提供相应的实机演示。链接会在后续给出。

相关文章:

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

引言&#xff1a;在实际工程项目中&#xff0c;为了提高系统的响应速度和稳定性&#xff0c;往往需要采用一定的控制算法进行目标跟踪。这里抛砖引玉&#xff0c;仅采用简单的PID算法进行目标的跟随控制&#xff0c;目标的识别依然采用yolo。对系统要求更高的&#xff0c;可以对…...

<JavaEE> TCP 的通信机制(一) -- 确认应答 和 超时重传

目录 TCP的通信机制的核心特性 一、确认应答 1&#xff09;什么是确认应答&#xff1f; 2&#xff09;如何“确认”&#xff1f; 3&#xff09;如何“应答”&#xff1f; 二、超时重传 1&#xff09;丢包的概念 2&#xff09;什么是超时重传&#xff1f; 3&#xff09…...

Spark任务调度与数据本地性

Apache Spark是一个分布式计算框架&#xff0c;用于处理大规模数据。了解Spark任务调度与数据本地性是构建高效分布式应用程序的关键。本文将深入探讨Spark任务调度的流程、数据本地性的重要性&#xff0c;并提供丰富的示例代码来帮助大家更好地理解这些概念。 Spark任务调度的…...

【论文阅读】Self-Paced Curriculum Learning

论文下载 代码 Supplementary Materials bib: INPROCEEDINGS{,title {Self-Paced Curriculum Learning},author {Lu Jiang and Deyu Meng and Qian Zhao and Shiguang Shan and Alexander Hauptmann},booktitle {AAAI},year {2015},pages {2694--2700} }1. 摘…...

C++简易线程池

原理说明&#xff1a; 1. 线程池创建时&#xff0c;指定线程池的大小thread_size。当有新的函数任务通过函数addFunction ()添加进来后&#xff0c;其中一个线程执行函数。一个线程一次执行一个函数。如果函数数量大与线程池数量&#xff0c;则后来的函数等待。 2. 线程池内部…...

【MATLAB】PSO粒子群优化LSTM(PSO_LSTM)的时间序列预测

有意向获取代码&#xff0c;请转文末观看代码获取方式~也可转原文链接获取~ 1 基本定义 PSO粒子群优化LSTM&#xff08;PSO-LSTM&#xff09;是一种将粒子群优化算法&#xff08;PSO&#xff09;与长短期记忆神经网络&#xff08;LSTM&#xff09;相结合的混合模型。该算法通过…...

产品经理学习-怎么写PRD文档

目录 瀑布流方法论介绍 产品需求文档&#xff08;PRD&#xff09;介绍 产品需求文档的基本要素 撰写产品需求文档 优先产品需求文档的特点 其他相关文档 瀑布流方法论介绍 瀑布流模型是一种项目的开发和管理的方法论&#xff0c;是敏捷的开发管理方式相对应的另一种方法…...

第3课 获取并播放音频流

本课对应源文件下载链接&#xff1a; https://download.csdn.net/download/XiBuQiuChong/88680079 FFmpeg作为一套庞大的音视频处理开源工具&#xff0c;其源码有太多值得研究的地方。但对于大多数初学者而言&#xff0c;如何快速利用相关的API写出自己想要的东西才是迫切需要…...

Spark编程实验四:Spark Streaming编程

目录 一、目的与要求 二、实验内容 三、实验步骤 1、利用Spark Streaming对三种类型的基本数据源的数据进行处理 2、利用Spark Streaming对Kafka高级数据源的数据进行处理 3、完成DStream的两种有状态转换操作 4、把DStream的数据输出保存到文本文件或MySQL数据库中 四…...

Flink去重计数统计用户数

1.数据 订单表&#xff0c;分别是店铺id、用户id和支付金额 "店铺id,用户id,支付金额", "shop-1,user-1,1", "shop-1,user-2,1", "shop-1,user-2,1", "shop-1,user-3,1", "shop-1,user-3,1", "shop-1,user…...

力扣:62. 不同路径(动态规划,附python二维数组的定义)

题目&#xff1a; 一个机器人位于一个 m x n 网格的左上角 &#xff08;起始点在下图中标记为 “Start” &#xff09;。 机器人每次只能向下或者向右移动一步。机器人试图达到网格的右下角&#xff08;在下图中标记为 “Finish” &#xff09;。 问总共有多少条不同的路径&…...

2022年全球运维大会(GOPS深圳站)-核心PPT资料下载

一、峰会简介 GOPS 主要面向运维行业的中高端技术人员&#xff0c;包括运维、开发、测试、架构师等群体。目的在于帮助IT技术从业者系统学习了解相关知识体系&#xff0c;让创新技术推动社会进步。您将会看到国内外知名企业的相关技术案例&#xff0c;也能与国内顶尖的技术专家…...

8868体育助力意甲罗马俱乐部 迪巴拉有望付出

8868体育助力意甲罗马俱乐部 迪巴拉有望付出 意甲罗马俱乐部是8868体育合作球队之一&#xff0c;本赛季&#xff0c;在意甲第14轮的比赛中&#xff0c;罗马客场2-1战胜萨索洛&#xff0c;积分上升到意甲第4位。 有报道称&#xff0c;迪巴拉在对阵佛罗伦萨的比赛中受伤&#xff…...

java设计模式实战【策略模式+观察者模式+命令模式+组合模式,混合模式在支付系统中的应用】

引言 在代码开发的世界里&#xff0c;理论知识的重要性毋庸置疑&#xff0c;但实战经验往往才是知识的真正试金石。正所谓&#xff0c;“读万卷书不如行万里路”&#xff0c;理论的学习需要通过实践来验证和深化。设计模式作为软件开发中的重要理论&#xff0c;其真正的价值在…...

小程序wx:if 和hidden的区别?

在小程序中&#xff0c;wx:if 和 hidden 是用于条件渲染的两种不同方式。 选择使用哪种方式取决于具体情况。如果条件变化频繁或节点包含复杂的子节点&#xff0c;可以考虑使用 wx:if 进行条件渲染&#xff1b;如果条件变化较少且节点结构简单&#xff0c;可以使用 hidden 控制…...

自动驾驶学习笔记(二十三)——车辆控制模型

#Apollo开发者# 学习课程的传送门如下&#xff0c;当您也准备学习自动驾驶时&#xff0c;可以和我一同前往&#xff1a; 《自动驾驶新人之旅》免费课程—> 传送门 《Apollo开放平台9.0专项技术公开课》免费报名—>传送门 文章目录 前言 运动学模型 动力学模型 总结…...

Linux Shell 015-文本双向覆盖重定向工具tee

Linux Shell 015-文本双向覆盖重定向工具tee 本节关键字&#xff1a;Linux、Bash Shell、文本双向覆盖重定向工具 相关指令&#xff1a;tee、echo、cat tee介绍 tee工具是从标准输入读取并写入到标准输出和文件&#xff0c;即&#xff1a;双向覆盖重定向&#xff08;屏幕输出…...

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

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

【mysql】数据处理格式化、转换、判断

数据处理 判断是否超时&#xff0c;时间是否大于当前时间计算分钟数时间格式化处理如果数值类型进行转换字符类型字符拼接case-when代替if-else判断数据空&#xff08;特殊&#xff1a;含空数据、空字符处理&#xff09; select /*判断是否超时&#xff0c;时间是否大于当前…...

深入探索Java中的UDP网络通信机制

在网络通信中&#xff0c;UDP&#xff08;User Datagram Protocol&#xff0c;用户数据报协议&#xff09;是一种无连接的协议&#xff0c;它在某些情况下比TCP更适合&#xff0c;尤其是在要求速度快、对数据准确性要求相对较低的场景下。本文将介绍如何使用Java进行UDP网络通信…...

Linux链表操作全解析

Linux C语言链表深度解析与实战技巧 一、链表基础概念与内核链表优势1.1 为什么使用链表&#xff1f;1.2 Linux 内核链表与用户态链表的区别 二、内核链表结构与宏解析常用宏/函数 三、内核链表的优点四、用户态链表示例五、双向循环链表在内核中的实现优势5.1 插入效率5.2 安全…...

树莓派超全系列教程文档--(61)树莓派摄像头高级使用方法

树莓派摄像头高级使用方法 配置通过调谐文件来调整相机行为 使用多个摄像头安装 libcam 和 rpicam-apps依赖关系开发包 文章来源&#xff1a; http://raspberry.dns8844.cn/documentation 原文网址 配置 大多数用例自动工作&#xff0c;无需更改相机配置。但是&#xff0c;一…...

微软PowerBI考试 PL300-选择 Power BI 模型框架【附练习数据】

微软PowerBI考试 PL300-选择 Power BI 模型框架 20 多年来&#xff0c;Microsoft 持续对企业商业智能 (BI) 进行大量投资。 Azure Analysis Services (AAS) 和 SQL Server Analysis Services (SSAS) 基于无数企业使用的成熟的 BI 数据建模技术。 同样的技术也是 Power BI 数据…...

前端导出带有合并单元格的列表

// 导出async function exportExcel(fileName "共识调整.xlsx") {// 所有数据const exportData await getAllMainData();// 表头内容let fitstTitleList [];const secondTitleList [];allColumns.value.forEach(column > {if (!column.children) {fitstTitleL…...

【解密LSTM、GRU如何解决传统RNN梯度消失问题】

解密LSTM与GRU&#xff1a;如何让RNN变得更聪明&#xff1f; 在深度学习的世界里&#xff0c;循环神经网络&#xff08;RNN&#xff09;以其卓越的序列数据处理能力广泛应用于自然语言处理、时间序列预测等领域。然而&#xff0c;传统RNN存在的一个严重问题——梯度消失&#…...

如何为服务器生成TLS证书

TLS&#xff08;Transport Layer Security&#xff09;证书是确保网络通信安全的重要手段&#xff0c;它通过加密技术保护传输的数据不被窃听和篡改。在服务器上配置TLS证书&#xff0c;可以使用户通过HTTPS协议安全地访问您的网站。本文将详细介绍如何在服务器上生成一个TLS证…...

现代密码学 | 椭圆曲线密码学—附py代码

Elliptic Curve Cryptography 椭圆曲线密码学&#xff08;ECC&#xff09;是一种基于有限域上椭圆曲线数学特性的公钥加密技术。其核心原理涉及椭圆曲线的代数性质、离散对数问题以及有限域上的运算。 椭圆曲线密码学是多种数字签名算法的基础&#xff0c;例如椭圆曲线数字签…...

ip子接口配置及删除

配置永久生效的子接口&#xff0c;2个IP 都可以登录你这一台服务器。重启不失效。 永久的 [应用] vi /etc/sysconfig/network-scripts/ifcfg-eth0修改文件内内容 TYPE"Ethernet" BOOTPROTO"none" NAME"eth0" DEVICE"eth0" ONBOOT&q…...

HarmonyOS运动开发:如何用mpchart绘制运动配速图表

##鸿蒙核心技术##运动开发##Sensor Service Kit&#xff08;传感器服务&#xff09;# 前言 在运动类应用中&#xff0c;运动数据的可视化是提升用户体验的重要环节。通过直观的图表展示运动过程中的关键数据&#xff0c;如配速、距离、卡路里消耗等&#xff0c;用户可以更清晰…...

A2A JS SDK 完整教程:快速入门指南

目录 什么是 A2A JS SDK?A2A JS 安装与设置A2A JS 核心概念创建你的第一个 A2A JS 代理A2A JS 服务端开发A2A JS 客户端使用A2A JS 高级特性A2A JS 最佳实践A2A JS 故障排除 什么是 A2A JS SDK? A2A JS SDK 是一个专为 JavaScript/TypeScript 开发者设计的强大库&#xff…...