06 Nov 2024
当无人机的可活动区域变大后,若保持分辨率不变,则 ego planner 里预先开辟的地图将会占据很大的内存,因此需要增大分辨率,来抵消一部分地图扩大带来的内存消耗。然而,这会给规划端带来一些挑战。
ego planner 的栅格地图的占据信息来自于 realsense 的深度图像,而深度值是存在有效范围的,如 D435 的理想范围是 0.3 m 到 3 m。即使是在理想深度测量范围内,也是有噪声的存在,而这个噪声则会体现在栅格地图中突然出现的障碍上。而 ego planner 是用于避障的,虚警的障碍会让规划的轨迹扭曲,增大无人机飞行控制的难度、里程计崩溃的概率。
通过增大深度滤波器的最小合法深度值,解决了因深度噪声、较大栅格体积共同造成的大虚警障碍,导致的轨迹规划过于扭曲甚至陷入障碍物的问题,目前可在室内使用 1 m 分辨率的栅格地图进行规划,室外测试也正常。带来的代价则是狭小区域内的避障能力的下降。
更彻底的解决办法是,不要使用那么小的分辨率,同时又想要节省内存,那么使用 oct 地图,或者将地图存在硬盘里,只加载当前位置周围的地图到内存中。
02 Nov 2024
利用自动化脚本,执行重复、确定的操作。
统一配置参数
算法以代码为实体部署后,会存在许多可调节的参数,当参数未被合理地给定,即使逻辑正确,算法的效果也可能并不如意。因此能够快速简便地调整参数便十分重要。
Fast-drone-xi35 里的模块较多,每个模块有不同的参数配置方法,可分成这几类:
在 launch 文件里给出参数具体值,使用 roslaunch
命令读取参数配置。
在 yaml 文件里给出参数具体值,使用 cv::FileStorage fsSettings(config_file, cv::FileStorage::READ);
函数读取参数配置文件,给变量赋值。如 VINS-Fusion-gpu。
在 yaml 文件里给出参数具体值,在 launch 文件里调用该 yaml 文件,最后使用 roslaunch
命令将参数值赋值到程序里的变量中。如 px4ctrl:
<launch>
<node pkg= "px4ctrl" type= "px4ctrl_node" name= "px4ctrl" output= "screen" >
<!-- <remap from="~odom" to="/vicon_imu_ekf_odom" /> -->
<remap from= "~odom" to= "/vins_fusion/imu_propagate" />
<remap from= "~cmd" to= "/position_cmd" />
<rosparam command= "load" file= "$(find px4ctrl)/config/ctrl_param_fpv.yaml" />
</node>
</launch>
对于整个工程来说,需要调整的参数分布在不同的 launch 或 yaml 文件中,所在的目录各异,并不能直观方便地统一调整,还需要动脑想一下这个参数在哪里。
为了解决这个问题,利用 GPT 大法,写了个 python 脚本,配合 yaml 文件,能够统一地管理修改频率较高的参数。原理是在 yaml 文件里给出某个包/模块的配置文件所在路径,之后利用正则表达式搜索该文件里的某一行,将其数值部分替换成我们想要的参数值。
yaml 文件如下:
# 工程顶层目录所在路径
path_prefix: /root/Fast-Drone-XI35/
# path_prefix: /home/orin01/Fast-Drone-XI35/
paths:
src/auto_search/target_merge/launch/target_merge.launch:
-
# 组别 id
<param name= "drone_id" value= "\d+" type= "int" /> : <param name= "drone_id" value= "2" type= "int" />
src/realflight_modules/VINS-Fusion-gpu/config/fast_drone_250.yaml:
-
# 里程计类型,0 不加偏置,1 加偏置(统一集群的世界坐标系)
"odometry_type: \\d+": "odometry_type: 1"
# 无人机个体 id
"drone_id: \\d+": "drone_id: 2"
# 偏置/坐标变换的数值
"single_offset: -*\\d+.\\d+": "single_offset: 2.0"
# 显示特征点追踪
"show_track: \\d+": "show_track: 0"
src/auto_search/search_plan/launch/search_plan.launch:
-
# search plan 判断是否到达给定点的阈值半径
<param name= "arrive_threshold" value= "\d+.\d+" type= "double" /> : <param name= "arrive_threshold" value= "0.5" type= "double" />
...
python 文件见 config_scipt/set_global_config.py
同时打开多个多窗口的终端
想要启动一架自主四旋翼的所有功能,需要十一个终端,数目众多,如果要启动集群,以八架为例,则需要打开八个大窗口,再将每个窗口分割为十一个窗口,并在每个窗口里输入所需的命令,极其繁杂。因此,必须利用脚本工具来自动化执行这些重复性、确定性的操作。
解决办法是利用 terminator 的布局配置文件,参考 使用 Terminator 在一个窗口中运行多个终端 :
将窗口分为多个部分后,将自定义的 Terminator 设置设置为默认非常容易。从弹出菜单中选择“首选> 项”,然后从打开的窗口顶部的选项卡中选择“布局”。接着你应该看到列出了“新布局”。只需单击底部的> “保存”,然后单击右下角的“关闭”。Terminator 会将你的设置保存在 ~/.config/terminator/> config 中,然后每次使用到时都会使用该文件。
你也可以通过使用鼠标拉伸来扩大整个窗口。再说一次,如果要保留更改,请从菜单中选择“首选项”,“布局”,接着选择“保存”和“关闭”。
针对 XI35,hh900 写了一个 terminator 的脚本,能够自动让每个终端进入容器,并预先打印出将要执行的命令。笔者在此基础上增加了非容器的版本。脚本见 terminator/config-orin01-nodocker ,若要阅读,倒序阅读方便查看有意义的命令。
PX4 配置文件导出与加载
为了简化其他无人机的飞控配置过程,应该使用地面站将已配好的无人机的飞控参数导出成文件,之后仍是使用地面站将该文件导入到其他无人机当中。
31 Oct 2024
I think this paper has three features:
Metric-Semantic mesh map
Distributed loop closure detection
Robust distributed trajectory estimation
Distributed loop closure detection
a –global descriptor–> b
a <–request 3D keypoints and descriptors– b
a – send 3D keypoints and descriptor –> b
Subsequently, robot β computes putative correspondences by matching the two sets of feature descriptors using nearest neighbor search implemented in OpenCV. From the putative correspondences, robot β attempts to
compute the relative transformation using Nistér’s five-point
method [79] and Arun’s three-point method [80] combined
with RANSAC [56]. Both techniques are implemented in the
OpenGV library [81]. If geometric verification succeeds with
more than five correspondences, the loop closure is accepted
and sent to the robust distributed trajectory estimation module.
GNC 渐近非凸性,用没那么非凸的替代(surrogate)函数序列来作优化,该函数序列会收敛到原来的损失函数。
Robust distributed initialization Between every pair of robots,
inlier loop closures (green→) lead to similar estimates for the alignment
between frames (green–>). Each outlier loop closure (red→) produces an
outlier frame alignment (red–>), which can be rejected with GNC.
Total views.
cowboys.
Hits