超维空间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站进行讲解。同时会提供相应的实机演示。链接会在后续给出。

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

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

相关文章

项目中使用Java中List.subList()的注意事项

使用介绍 在Java中&#xff0c;subList是List接口的一个方法&#xff0c;用于获取原始列表的子列表 方法的声明如下 List<E> subList(int fromIndex, int toIndex);fromIndex&#xff1a;起始索引&#xff08;包括&#xff09;toIndex&#xff1a;结束索引&#xff08…

解密垃圾邮件分类:基于SVM的数据挖掘项目

垃圾邮件&#xff08;Spam&#xff09;的泛滥成灾一直是电子邮件系统中的一个严峻问题。随着垃圾邮件技术的不断演变&#xff0c;传统的过滤方法逐渐显得力不从心。因此&#xff0c;本项目旨在利用支持向量机&#xff08;SVM&#xff09;这一强大的机器学习工具&#xff0c;实现…

git、gitee、github、gitlab 区别以及功能

请直接看原文 原文链接:git、gitee、github、gitlab 区别以及功能_agit gitee-CSDN博客 --------------------------------------------------------------------------------------------------------------------------------- Git git 是一种版本控制系统&#xff0c;是…

Activemq存储KahaDb详解

引言 ActiveMQ在不提供持久化的情况下&#xff0c;数据保存在内存中&#xff0c;一旦应用崩溃或者重启之后&#xff0c;数据都将会丢失&#xff0c;这显然在大部分情况下是我们所不希望的。对此ActiveMQ提供了两种持久化方式以供选择。 kahaDB kahaDB是一个基于文件&#xf…

WPF+Halcon 培训项目实战(10):HS组件绘制图案

文章目录 前言相关链接项目专栏运行环境匹配图片模板匹配加载模板文件运行结果 绘制十字标 WPF HS组件绘制图像绘制和生成的区别 前言 为了更好地去学习WPFHalcon&#xff0c;我决定去报个班学一下。原因无非是想换个工作。相关的教学视频来源于下方的Up主的提供的教程。这里只…

元旦特辑:Note6---选择排序

目录 前言❌ 1. 基本思想⚠️ 2. 直接选择排序&#x1f7e2; 2.1 思路分析✳️ 2.2 代码实现❎ 2.2.1 sort.h 2.2.2 sort.c 2.2.3 test.c 2.3 问题解决❇️ 2.3.1 sort.c修改 2.4 特性总结✅ 3. 堆排序&#x1f535; 3.1 代码实现&#x1f3e7; 3.2 特性总结&…

神经元科技发布AI agent—“萨蔓莎”

今天神经元科技发布AI agent—“萨蔓莎“&#xff08;Samantha &#xff09;&#xff01; 取名“萨蔓莎”&#xff0c;是来自于一部讲述AI的电影《HER》。 电影讲述的是电影讲述男子西奥多汤布里&#xff08;Theodore Twombly&#xff0c;饰&#xff09;与拟人化萨曼莎&#…

mysql2pgsql

使用pgloader进行迁移 pgloader是一个强大的数据迁移工具&#xff0c;专为将不同数据库之间的数据迁移到PostgreSQL而设计。它支持从MySQL到PostgreSQL的迁移&#xff0c;并提供了一种简单且灵活的方式来转移数据。 安装pgloader 使用pgloader迁移数据 1、命令行方式 2、脚…

【AI】注意力机制与深度学习模型

目录 一、注意力机制 二、了解发展历程 2.1 早期萌芽&#xff1a; 2.2 真正意义的注意力机制&#xff1a; 2.3 2015 年及以后&#xff1a; 2.4 自注意力与 Transformer&#xff1a; 2.5 BERT 与预训练模型&#xff1a; 三、基本框架 1. 打分函数&#xff08;Score Fun…

Vue常见面试问答

vue响应式数据 vue2 Vue2 的对象数据是通过 Object.defineProperty 对每个属性进行监听&#xff0c;当对属性进行读取的时候&#xff0c;就会触发 getter&#xff0c;对属性进行设置的时候&#xff0c;就会触发 setter。 /** * 这里的函数 defineReactive 用来对 Object.def…

如何正确使用docker搭建redis服务器,安装gcc和make以及出现错误时的解决办法

搭建redis服务器 目录 搭建redis服务器 &#xff08;1&#xff09;开启docker&#xff0c;并查看是否开启成功 &#xff08;2&#xff09;启动上面创建的ssrf容器&#xff0c;并进入ssrf容器 &#xff08;3&#xff09;进入opt&#xff0c;然后下载redis-5.0.5.tar.gz &a…

GitHub Copilot 快速入门

一简介 GitHub Copilot是一个AI编程助手&#xff0c;它能够为开发者提供代码建议和自动完成功能。Copilot使用自然语言处理技术来理解代码的语义&#xff0c;并根据上下文提供智能化的代码建议。通过使用Copilot&#xff0c;开发者可以提高编码效率&#xff0c;减少错误率&…

Apache SSI 远程命令执行漏洞

一、环境搭建 二、访问upload.php 三、写shell <!--#exec cmd"id" --> 四、访问 如图所示&#xff0c;即getshell成功&#xff01;​

Zookeeper-Zookeeper应用场景实战

1. Zookeeper Java客户端实战 ZooKeeper应用的开发主要通过Java客户端API去连接和操作ZooKeeper集群。 可供选择的Java客户端API有&#xff1a; ZooKeeper官方的Java客户端API。 第三方的Java客户端API&#xff0c;比如Curator。 ZooKeeper官方的客户端API提供了基本的操作…

宝塔部署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…

java 什么是变量和字面量?

什么是变量&#xff0c;怎么理解的&#xff1f; 变量其实就是内存当中存储数据的最基本的单元。 一个存储数据的盒子&#xff0c;一个存储数据的单元。 什么是字面量&#xff0c;怎么理解&#xff1f; 整数型字面量&#xff0c;浮点型的字面量&#xff0c;布尔类型字面量&#…

sklearn学习的一个例子用pycharm jupyter

环境 运行在jupyter 进行开发。即一个WEB端的开发工具。能适时显示开发的输出。后缀用的是ipynb.pycharm也可以支持。但也要提示按装jupyter. 或直接用andcoda 这里我们用pycharm进行项目创建 pip install -i https://pypi.tuna.tsinghua.edu.cn/simple jupyterlab pip ins…

API服务的快速搭建和测试

API服务的快速搭建和测试 使用Python的FastAPI迅速搭建一个简单API from fastapi import FastAPI, Request from transformers import AutoTokenizer, AutoModel import uvicorn, json, datetime import torch# 设置CUDA设备信息 DEVICE "cuda" DEVICE_ID "0…

在vim中映射类似于Windows编辑器的快捷键

vim编辑器的历史比较久&#xff0c;继承于vi&#xff0c;这个编辑器就更早了。可能拜于年代所赐&#xff0c;里面的快捷键设计似乎不是那么“现代化”&#xff0c;和很多现在的编辑器的热键设计出入很大&#xff0c;里面的命令更不是一般人能记得住的。 我一直知道vim可以rema…

QT 利用开源7z 实现解压各种压缩包,包括进度条和文件名的显示(zip,7z,rar,iso等50多种格式)

想做一个winRAR一样的解压软件吗?很简单,利用开源的7z库就能实现。我看网上其他人说的方法不敢苟同,误人子弟。以前自己在项目中使用过7z,这次又有需要,就想记录下来。如果你研究过如何用7z的话,一定知道7z的每一个GUID都代表了一种格式,50多种GUID也就有50多个格式,最…