基于激光雷达的无人机相互避障

本框架是基于激光雷达的无人机群自主避障代码:
  • 其主体框架利用ORCA算法,他是经典的多智能体相互避障算法,此版本只能规避动态障碍物,不能规避环境形成的静态障碍物
  • 我们对ORVA算法稍作修改,使其可以分布式部署 ,并且将仿真代码修改为uav实测代码
  • ORCA算法需要知道其他智能体的绝对位置和速度作为算法输入,因此我们需要模块【1】和【2】来补充完成
  • 模块【2】是利用将lidar安装在当前uav上,并用其检测和估计其他无人机的相对位置和速度
  • 因为不满足ORVA算法需要绝对位置和速度的条件,因此需要利用模块【1】来估计当前uav的位置进行结合

【配置规范】不同的包安装在不同的工作空间中,方便管理,如catkin_ws_realsense,catkin_ws_vins,catkin_ws_lidar,catkin_ws_orca

1. 基于VIO/LIO的uav自身位置估计

1\] LIO 因为无人机安装了Lidar,所以用LIO比较好 待安装。。。 \[2\] VIO VIO使用Vins,是基于D435深度相机的,具体安装参考[D435i+vins-Fusion+ego-planner+yolo无人机避障实测](https://blog.csdn.net/dueen1123/article/details/126747231?spm=1001.2014.3001.5501)中vins部分 ```bash roslaunch realsense2_camera rs_camera_vins.launch rosrun vins vins_node ~/catkin_ws_vins/src/VINS-Fusion/config/realsense_d435i/realsense_stereo_imu_config.yaml ``` ### 2. 利用Lidar检测并估计其他uavs位置和速度 代码下载链接: 新建一个catkin_ws_lidar的工作空间 在其中先配置好激光雷达livox的SDK以及ROS版本的SDK,[参考链接在此](https://hitxjf.github.io/2023/02/12/Mid-360%20%E5%BF%AB%E9%80%9F%E9%85%8D%E7%BD%AE%E6%8C%87%E5%8D%97/) 然后将lidar_esti放在同一工作空间一起编译 代码运行如下: ```bash # 启动激光雷达 roslaunch livox_ros_driver2 rviz_MID360.launch cd ~/catkin_ws_lidar/src/lidar_esti/scripts # 运行高反无人机检测 python3 multi_highRreflect_detect.py # lidar到orca转换脚本 python lidar2orca.py ``` 其中`multi_highRreflect_detect.py`和`lidar2orca.py`中的`DETECT_UAV_NUM`变量,需要根据实际uav个数修改 ### 3. ORCA集群避障算法 代码链接: 实测代码不同的无人机需要添加不同的`node_0_true.cpp`,以及相对应的`rvo_node_true.launch`和`node_0_true.sh` (1)`rvo_node.h`修改`copy_num_agent`变量,改为本次实测的uav个数 ```cpp int copy_num_agent = 2; // 复制智能体数量 ``` (2)`node_0_true.cpp`,修改如下代码 ```cpp void rvo_true_velCallback(const UAVPosVel::ConstPtr &sub_msg){ // ... // 用哪架无人机,序号改成几 float x = new_velocities[0]->x(); float y = new_velocities[0]->y(); float z = new_velocities[0]->z(); // ... } ``` (3)`rvo_node_true.launch`更改为当前的 `node_0_true`节点 (4)`node_0_true.sh`后面的目标点数量,修改与总uav数量一致,并且是第几架无人机,对应的目标点位置才赋值 ```bash #!/bin/bash rosrun rvo_ros set_goals_client_0 default 1 1 1 0 0 0 sleep 8 rosrun rvo_ros set_goals_client_0 default 4 1 1 0 0 0 sleep 6 ``` 运行如下: ```bash #启动飞机px4飞控 #启动vins绝对定位 #启动lidar相对定位 cd ~catkin_ws_orca/src/rvo_ros/scripts # 无人机通信 python multirotor_communication.py iris 0 # 无人机悬停 python hover.py iris 1 vel # 启动壁障算法 roslaunch rvo_ros rvo_node_true.launch # 设置目标点 bash node_0_true.sh ``` ============================ 以下可以忽视 ========================== ORCA是主要的避障算法 ORCA需要一个自定义话题的输入,也就是一个包含速度和位置的消息 但c++和python自定义消息稍有不同,不能直接引用头文件,然后直接用消息名称使用,如下 ```cpp #include "UAVPosVel.h" void rvo_true_velCallback(const UAVPosVel::ConstPtr &sub_msg); ``` 首先,#include可能难以直接定位到UAVPosVel.h,需要在cmakelist中的include_directories添加其生成路径,即xxx/devel/include/package_name 其次,UAVPosVel.h中的类不叫UAVPosVel,他生成了一个模板函数,所以使用时应该重新定义 总结如下: ```bash include_directories( include ${catkin_INCLUDE_DIRS} ${PROJECT_SOURCE_DIR}/include/3d_library # 确保这里包含了3d_library目录 /home/tju/catkin_ws_orca/devel/include/rvo_ros ) ``` ```cpp #include "UAVPosVel.h" typedef rvo_ros::UAVPosVel_> UAVPosVel; void rvo_true_velCallback(const UAVPosVel::ConstPtr &sub_msg); ```

相关推荐
威视锐科技2 小时前
软件定义无线电36
网络·网络协议·算法·fpga开发·架构·信息与通信
牧歌悠悠2 小时前
【Python 算法】动态规划
python·算法·动态规划
JINX的诅咒2 小时前
CORDIC算法:三角函数的硬件加速革命——从数学原理到FPGA实现的超高效计算方案
算法·数学建模·fpga开发·架构·信号处理·硬件加速器
明天不下雨(牛客同名)3 小时前
为什么 ThreadLocalMap 的 key 是弱引用 value是强引用
java·jvm·算法
lisw054 小时前
DeepSeek原生稀疏注意力(Native Sparse Attention, NSA)算法介绍
人工智能·深度学习·算法
喝拿铁写前端5 小时前
SmartField AI:让每个字段都找到归属!
前端·算法
莫有杯子的龙潭峡谷5 小时前
3.31 代码随想录第三十一天打卡
c++·算法
LuckyLay5 小时前
LeetCode算法题(Go语言实现)_22
算法·leetcode·golang
云卓SKYDROID5 小时前
无人机DSP处理器工作要点!
人工智能·无人机·科普·云卓科技
BingLin-Liu5 小时前
蓝桥杯备考---》贪心算法之矩阵消除游戏
算法·游戏·贪心算法