Acta Aeronautica et Astronautica Sinica ›› 2023, Vol. 44 ›› Issue (18): 28334-028334.doi: 10.7527/S1000-6893.2023.28334
• Reviews • Previous Articles Next Articles
Yubin YUAN, Yiquan WU(), Langyue ZHAO, Jinlin CHEN, Qichang ZHAO
Received:
2022-11-29
Revised:
2022-12-31
Accepted:
2023-03-16
Online:
2023-09-25
Published:
2023-03-21
Contact:
Yiquan WU
E-mail:nuaaimage@163.com
Supported by:
CLC Number:
Yubin YUAN, Yiquan WU, Langyue ZHAO, Jinlin CHEN, Qichang ZHAO. Research progress of UAV aerial video multi⁃object detection and tracking based on deep learning[J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(18): 28334-028334.
Table 2
Comparison of main multi⁃object detection algorithms for UAV based on two⁃stage detection
问题 | 网络 | 改进措施 | 优势 | 劣势 |
---|---|---|---|---|
小目标增多 | MS-Faster R-CNN[ | Multi-Stream CNN作为主干,使用具有不同卷积核尺寸的金字塔结构提取特征 | 精确度高 | 速度较原始网络慢 |
Cascade R-CNN[ | 锚框尺寸减半,预估的目标数量增加一倍 | 小目标精度高 | ||
HDHNet[ | 多分辨率输入,多个深度网络维护多个位置信息,利用高分辨率图像优点 | 保持图像高分辨率特征 | 不能实时 检测 | |
ResNet-18+HOG[ | 利用ResNet-18第1和第3卷积层的特征,获得深层特征,利用颜色直方图和HOG获取手工特征补充深层特征 | 嵌入目标先验 特征 | 环境变化快时检测效果差 | |
HRDNet[ | MD-IPN使用多个深度主干维护多个位置信息,高分辨率输入浅层网络,低分辨率输入深层网络 | 保留了更多位置信息并降低计算成本 | ||
MPFPN+SSAM[ | MPFPN恢复缺失特征,SSAM削弱背景噪声,在Fast R-CNN阶段采用级联结构 | 目标特征丰富, 噪声影响小 | 训练样本 不均衡 | |
单维度信息不足 | Aerial MPT Net[ | Siamese与LSTM和图卷积神经网络配合,融合外观、时间和图形信息 | 提取目标多种 信息 | 鲁棒性较差 |
DetectoRS[ | 在HTC上引入递归特征金字塔,对目标特征多次对比 | 边界框比例准确 | ||
Track R-CNN[ | 扩展具有3D卷积的Mask R-CNN,引入语义分割 | 精度达到像素 级别 | ||
SyNet[ | 加权融合Cascade R-CNN和CenterNet的检测结果 | 检测精度高 | 参数多速度慢 | |
D2Det[ | 采用密集局部回归,子区域进行采样,自适应加权获得特征 | 定位与分类精确 | ||
类别稀疏 不均 | ClusDet[ | CPNet网络生成目标簇区域,使用ScaleNet网络估计这些区域的目标比例 | 结合聚类和检测 | 数据较少时,性能受限 |
GDF-Net[ | 应用扩展卷积网络细化密度特征,提供更大的感受野并生成全局密度融合特征 | 网络召回率和 精确度高 | ||
DSHNet[ | CBS和BBH双路径方式处理尾类和头类 | 尾类目标检测 精确 | 速度慢 | |
检测干扰 | Cascade ResNet50[ | 在主干中引入了DeForm卷积层,FPN融合不同尺度特征,集成RPN提取感兴趣区域 | 提高了视点 变化的适应性 | 网络效率低 |
ACM+ARM+ODM[ | ACM获取上下文信息,ARM实现二分类和默认框粗略回归,ODM则细化选定的框以执行多类分类 | 可实时检测 | 遮挡目标 精度低 | |
NDFT[ | 对抗学习训练检测模型 | 无需额外适配 | ||
MSOA-Net[ | MSFAF多层次自适应地聚合层次特征图,处理目标的比例变化;RATH-Net引导位置敏感子网络增强目标并抑制噪声 | 相近干扰降低 | 泛化能力弱 | |
尺度变化带来的漏检和误检 | RRNet[ | 加入重回归模块,Ada Resampling自适应增强数据 | 误判率低 | |
FPN+SRM+RFEB[ | SRM细化多尺度特征,RFEB增加高级语义特征 | 精度高,速度快 | ||
PENet[ | MRM增强数据均衡,粗检测器预测目标簇的中心点,精细检测器定位小目标精确位置 | 小目标检测 精度高 | ||
Deep 6-ReLU[ | 线性单元卷积来挖掘空间-光谱特征 | 多条件下表现 良好 | 异常检测弱 | |
ECascade RCNN[ | Trident-FPN网络提取多尺度特征并融合,双头注意机制提高检测性能 | 大、小目标都取得良好性能 | ||
FPN + Cascade R-CNN[ | FPN生成多尺度特征,Cascade R-CNN架构用于训练检测器 | 泛化性好 | 尾类目标 性能差 |
Table 3
Comparison of main multi⁃object detection algorithms for UAV based on one⁃stage detection
问题 | 网络 | 改进措施 | 优势 | 劣势 |
---|---|---|---|---|
小目标增多 | UAV-YOLO[ | ResNet单元替换为Res Unit_2,连接相同宽度和高度的2个单元 | 小目标检测效果好 | |
YOLO V5m-opt[ | 调整深度和宽度,YOLO V5配置为任意大小;小目标分支加倍,大目标分支减半 | 参数少,精度高 | ||
YOLO V3+ Retina Net[ | YOLO V3检测常规目标,Retina Net检测小目标 | 检测精度高 | 速度变慢 | |
DNOD[ | VGG网络提取特征,与疑似区域的位置信息结合起来进行二次识别 | 小目标漏检率低 | 资源占用多 | |
单维度信息不足 | SlimYOLO V3[ | YOLO V3网络的3个检测头前的第5和第6卷积层之间,插入3个SPP | 参数少,速度快 | 修剪不灵活 |
TA-ResNet[ | 分别提取各个维度上的注意力特征,组成跨维度注意力特征三元组,再将三元组特征加权融合 | 保留了大量空间信息 | 融合模块的 计算代价高 | |
YOLO V4eff[ | 用4组Cross-stage-partial进行主干网络与颈部网络的连接 | 精度高 | ||
类别稀疏 | DS YOLO V3[ | 在YOLO V3增加2个模块,多尺度感知决策鉴别网络,以检测不同尺度目标;多尺度融合的通道注意力模块实现信息互补 | 精度高,硬件资源占用少 | |
检测干扰 | FS-SSD[ | 利用反卷积模块和特征融合模块生成的2个特征金字塔共同检测 | 小目标检测性能高 | 速度慢 |
SPB-YOLO[ | 联合Bottleneck架构与Strip Module设计SPB模块,嵌入到YOLO V5网络,并加一个检测头实现密集检测 | 目标宽度-高度关系 | ||
尺度变化带来的 漏检和误检 | D-A-FS SSD[ | 通过扩展卷积来扩展感受域,注意力网络抑制无效背景信息,结合低级特征与高阶特征 | 特征表达强,小目标检测精度高 | 正负样本不均衡 |
DAGN[ | 注意力块与特征连接结合区分特征层,将标准卷积替换为深度可分离卷积,Gaussian NMS提高密集区域性能 | 未增加额外计算 | ||
DAN[ | 以RetinaNet模型为基础,采用大尺度方差的更密集锚定尺度,利用SE模块捕获通道相关性 | 能自适应地校准信道特性响应 | 数据不均衡时效果差 | |
F-SSD[ | 从不同层的多个特征图中生成目标定位并识别目标类别,多尺度特征融合模块融合低层特征和高层特征 | 误报率低 | 小目标丢失过多 | |
FAANet[ | RepVGG网络作为主网络,融合空间注意模块和特征对齐聚合模块,集成多尺度特征 | 精度高,速度快 | ||
RetinaNet50[ | 更改了锚点大小以检测小目标,在FPN的P3和P4中添加CONV层,融合较高级别特征和较低级别的特征 | 遮挡时效果稳健 | 相机快速移动时效果差 | |
推理速度慢 | DroNet[ | 以Tiny YOLO为基准,减少每个层的过滤器数量和粗修剪整层 | 网络参数少 | 位宽高 |
MultEYE[ | 将YOLO V4的主干替换为CSPDarkNet53 Lite,ENet做为分割头 | 参数量降到1/4 | ||
Com Net[ | 删除MobileNetv2的平均池化层和最后一个卷积层,替换YOLO V3网络中的DarkNet53 | 减少模型参数和计算 成本 | ||
SSD + PeleNe[ | 在SSD前加入PeleNet,加宽网络层补偿精度,残差块使用1×1卷积核替代3×3卷积核 | 计算成本低 | ||
YOLO V5+ Wide RCNN[ | 使用基于YOLO V5检测结果的目标块作为目标特征提取的输入,目标特征由Wide RCNN提取 |
Table 4
Comparison of main algorithms for multi⁃object tracking for UAV based on target feature modeling
特征 | 网络 | 跟踪方法 | 优势 | 劣势 |
---|---|---|---|---|
外观 特征 | SCTrack-3L[ | 三阶段数据关联方案,基于目标外观模型,结合空间距离和显式遮挡处理单元,依赖被跟踪目标的运动模式和环境约束 | 遮挡目标效果好 | |
OSIM[ | 宽残差网络提取目标外观特征,使用级联匹配进行数据关联 | 实时性强 | 阴影易引起误判 | |
SBMA[ | 计算目标与其他目标之间的外观相似性,Social LSTM获取目标运动预测,加权外观相似性和运动预测生成目标关联 | 降低了上下文变化的影响 | ||
KM-Tracker[ | Kuhn-Munkres算法对目标建立对应关系,并使用目标的颜色直方图比较来处理目标在摄像机视野中消失和出现的情况 | 重进入目标与小目标跟踪效果好 | ||
DQN[ | 利用四元组损失函数研究特征空间,使用6层连接的深度CNN挖掘空间-光谱特征 | 效率高 | ||
光流 特征 | CNN + optical flow[ | CNN实现特征提取和分类,采集光流矢量视为运动目标,使用KLT跟踪实现多目标跟踪 | 跟踪器累积 误差低 | 速度慢 |
KLT[ | 提取目标光流特征的测量值,对齐到同一坐标系中,R-RANSAC算法滤出杂波中的目标 | 低海拔视频跟踪效果好 | 视野边缘目标 跟踪差 | |
Flow-Tracker[ | 匈牙利算法替换IOU tracker的贪婪数据关联方式,使用光流网络估计偏移量进行定位 | 跟踪稳定,误检率低 | 速度慢 | |
VOFT[ | 计算密集光流,根据光流轨迹的投票结果测量目标 相似性 | 低帧率的效果好 | ||
GGDTrack[ | 使用稀疏光流特征点生成KLT轨迹,将目标锚点与目标框连接,加入长连接将完全跟踪分解为单个优化来 解决 | 无需额外优化 | ||
多维 特征 | Multi-vehicle Tracker[ | ResNet-18提取重识别特征,结合历史和位置信息构建相似矩阵,匈牙利算法帧间目标匹配 | 可重跟踪误判 目标 | |
TNT[ | 构建多尺度TrackletNet作为分类器,在似然估计中结合时间和空间特征,获得关联信息 | 相机快速移动时跟踪效果稳健 | 相机旋转时效果差 | |
TACF[ | 融合上下文注意、维度注意和时空注意多级视觉注意力 | 遮挡、背景噪声下性能显著提高 | ||
PAS Tracker[ | 综合目标的位置、外观和大小信息,计算所有检测和轨迹之间的相似性度量,用匈牙利方法完成轨迹的匹配 | 密集空间的误报率低 | 过于依赖检测结果 | |
相关滤 波器 | TSD[ | 将跟踪过程划分为多个时隙,采用BACF扩大搜索区域 | 训练冗余少 | |
Keyfilter-Aware[ | 以BACF作为基准滤波器,融合间歇性上下文学习策略,从周期性关键帧中生成Keyfilter | 识别能力高 | ||
MOSSE[ | 使用前两帧进行初始化,使用自然对数变换和离散傅里叶变换对其进行初始化,转至频域表示,生成合成目标 | 可在CPU上实时运行 | 无法在运行条件下验证 |
Table 5
Comparison of multi⁃object tracking algorithms for UAV based on target trajectory prediction
类别 | 文献 | 跟踪策略 | 优点 | 缺点 |
---|---|---|---|---|
卡尔曼滤波 | [ | Squeeze Net网络实现运动目标分类,卡尔曼滤波进行目标跟踪 | 可实时执行多个任务 | |
[ | 假设目标恒速移动,联合卡尔曼滤波,构造所有目标的所有情况,基于联合概率数据关联似然,通过选通测量值的加权和更新状态预测 | 可在短时间内补偿检测损失 | 未建模运动可能导致虚假跟踪 | |
[ | 目标的质心作为跟踪的输入,通过最小ROI大小消除虚假ROI | 跟踪效率高 | 目标多时效果差 | |
[ | Car-Reid数据集训练残差网络提取目标外观信息,使用卡尔曼滤波提取目标运动信息,整合到成本矩阵,由匈牙利匹配算法得到跟踪结果 | 目标外观相似和运动突变可稳定跟踪 | ||
[ | 卡尔曼滤波器提取目标运动信息并更新,匈牙利算法得到跟踪结果 | 快速移动时稳定跟踪 | ||
[ | 卡尔曼滤波和单应性变换运动补偿模型,使用单应矩阵修改预测位置以抵抗位置漂移 | 旋转目标跟踪效果好 | ||
[ | 利用态势评估信息来提高跟踪性能,基于目标运动的轨迹构建评估信息,用于增强估计 | 参数不可自适应 | ||
DeepSORT | [ | 通过不同的预测网络生成目标边界框,根据置信度对检测框进行过滤,对所有轨迹和检测结果进行级联匹配 | 解决了类别不均衡问题,计算复杂度低 | 无法实时 |
[ | 在MARS数据集上预训练生成关联矩阵,结合外观特征和运动信息,在DeepSort框架实现跟踪 | 目标被遮挡后仍能跟踪 | 密集状态下跟踪效果差 | |
[ | 对匹配和未匹配的目标分别处理,在DeepSORT框架下实现了UAV视角下的目标跟踪 | 在无需精确定位的情况下效果好 | 速度慢 | |
[ | 使用YOLO V5获得目标的实时位置,联合DeepSORT框架实现了目标的速度测量 | 集成了速度估计和流量分析 | 存在质心偏移误差,计算成本高 | |
[ | 设计了深度关联网络,根据深度特征相似性对目标进行评分,与深度关联度量融合,传递到DeepSORT框架中 | 可实现自适应重新校准 | 复杂环境下会跟丢 | |
[ | 设计了MS-Faster R-CNN检测视频流中的目标,利用从边界框推断的视觉外观,结合Deep SORT描述视频序列中的目标轨迹 | 速度快 | 速度和精度不可兼得 | |
[ | 用OSNet替换DeepSORT中的简单特征提取器,利用全局线索将其关联到轨迹中,EMA-Bank以实现小轨迹之间关联 | 消除了重复检测导致的冗余轨迹 | 检测结果受数据集限制 | |
[ | 利用轻型ShuffleNet V2网络对VeRi数据进行车辆重新识别训练,得到车辆的外观模型,加入到DeepSORT中 | ID切换少 | ||
[ | 利用了目标在被遮挡早期视频中的信息,预测被遮挡目标的位置 | 解决了目标遮挡 | 复杂场景不稳定 |
Table 6
Comparison of other multi⁃object tracking algorithms for UAV
类别 | 文献 | 跟踪策略 | 优点 | 缺点 |
---|---|---|---|---|
SOT | [ | 将基于数据关联的跟踪方法与使用压缩跟踪方法的目标跟踪相结合,将单目标跟踪与假设匹配相结合用于目标重识别 | 小目标跟踪、目标遮挡时效果好 | 外观突变时匹配不准确 |
[ | 将物体运动和无人机运动分别视为个体运动和全局运动,利用Social LSTM网络估计个体运动,构建连体网络来生成全局运动 | UAV悬停时效果好 | 速度慢 | |
[ | 使用OSNet网络提取ReID特征表示边界框,计算每对边界框与两条轨迹的欧氏特征距离 | 具有全尺度特征学习能力 | 长期消失和不规则运动时效果差 | |
[ | 利用Micro CNNs负责单个目标跟踪任务,使用双流CNN从每个目标的两个连续帧中提取一组特征,以预测目标在当前帧中的位置 | 目标较多时参数仍保持合理 | 复杂背景 效果差 | |
记忆 网络 | [ | Siamese网络、LSTM和图卷积神经网络融合外观、时间和图形信息,通过SE卷积自适应加权,自适应欧氏距离进行连续帧中的目标关联 | 融合了外观、时间和图形信息 | 搜索区域不可调整 |
[ | 双向LSTM,一组用于前向序列,另一组用于时间上的后向序列,将LSTM的完全连接层替换为卷积层 | 保留了特征信息和轨迹的长时信息 | ||
IOU | [ | 引入上下文感知IOU引导跟踪器,利用多任务双流网络和离线参考建议生成策略,仅从ResNet-50的block3和block4中提取特征 | 显著遮挡和视点变化情况跟踪稳定 | |
[ | 匈牙利算法替代原始IOU tracker使用的贪婪方法进行轨迹分配,使用特定阈值筛选假阳性轨迹,使用中值流跟踪器补偿假阴性跟踪轨迹 | 视觉跟踪器能够补偿检测丢失 | 未利用检测器提取的图像 特征 | |
[ | 将目标跟踪中关注的特定实例替换为同一类目标,对给定目标基于实例的先验知识进行建模和根据当前框架中的不同提议估计IOU分数 | 速度超过25 FPS | 更新受到目标周围背景区域的干扰 | |
JDT | [ | FairMOT网络为基础设计了Single-Shot MOT网络,使用EfficientNet作为主干网络生成3个多尺度特征图,通过双向特征金字塔网络进行特征融合 | 推理速度快 | 具有较多遮挡时目标易丢失 |
[ | 以RepVGG网络作主网络,集成多尺度特征,采用JDT框架跟踪 | 实时性强 |
Table 7
Main data set of multi object detection and tracking for UAV
数据集 | 属性 | 视频帧 | 标注 数量 | 分辨率 | 任务 | 下载链接 |
---|---|---|---|---|---|---|
Stanford Drone[ | 行人、自行车、汽车、滑板手、高尔夫球车和公共汽车 | 929.5 k | 19.5 k | 1 417×2 019 | MOT&MTD | http:∥cvgl.stanford.edu/projects/uav_data/ |
UAVDT[ | 各种天气条件、目标遮挡和距地高度,广场、干道、收费站、高速公路等场景 | 80 k | 841.5 k | 1 080×540 | MOT&MTD | https:∥sites.google.com/view/grli-uavdt |
VisDrone2018[ | 行人、汽车、自行车和三轮车等 | 40 k | 183.3 k | 3 840×2 166 | MOT&MTD | https:∥github.com/VisDrone/VisDrone-Dataset |
VisDrone2019[ | 增加了数据集小目标数量和背景干扰 | 261.9 k | 2.6 M | 3 840×2 166 | MOT&MTD | https:∥github.com/VisDrone/VisDrone-Datase |
BIRDSAI TIR[ | 包含多尺度、背景杂波、角度旋转和运动模糊等变化,类别包括人和动物 | 162 k | 270 k | 640×480 | MOT&MTD | https:∥sites.google.com/view/elizabethbondi/dataset |
CARPK[ | UAV视角首个停车场数据集,单个场景最大车辆数为188 | 1.5 k | 90 k | 1 280×720 | MTD | https:∥lafi.github.io/LPN/ |
DAC-SDC[ | 95个类别 | 150 k | 640×360 | MTD | www.github.com/xyzxinyizhang/2018-DAC-System-Design-Contest | |
MOR-UAV[ | 涵盖夜间、遮挡、摄像机运动、天气条件等场景 | 10 k | 90 k | 1 280×720、1 920×1 080 | MTD | https:∥arxiv.org/abs/2008.01699 |
Drone Vehicle[ | RGB和热红外图像,涵盖照明、遮挡和比例变化,包括城市道路、住宅区、停车场、高速公路等场景 | 31.1 k | 88.3 k | 840×712 | MTD | https:∥github.com/VisDrone/DroneVehicle |
AU-AIR[ | 多模式传感器采集,包括人、汽车、公共汽车、面包车、卡车、自行车、摩托车和拖车等类别 | 32.8 k | 132 k | 1 920×1 080 | MTD | https:∥bozcani.github.io/ auairdataset |
MOHR[ | 包括汽车、卡车、建筑、洪水破坏和坍塌等类别 | 10.7 k | 90 k | 5 482×3 078、7 360×4 912、 8 688×5 792 | MTD | https:∥www.sciencedirect.com/science/article/pii/S09252 31220314338?via%3Dihub |
UVSD[ | 具有多个格式注释,其中98 600个目标实例具有实例级语义注释 | 5.8 k | 98.6 k | 960×540到5 280× 2 970 | MTD | https:∥github.com/liuchunsense/UVSD |
Table 9
Multi object tracking evaluation indicators
名称 | 公式 | 含义 |
---|---|---|
MOTA↑ | 跟踪准确度,与物体位置的估计精度无关 | |
MOTP↑ | 跟踪精度, | |
HOTA↑ | 高阶跟踪精度,A为数据关联分数,TP 为整个视频中检测目标被正确跟踪的数量 | |
IDF1↑ | 正确识别的检测与平均真实数和计算检测数之比,强调关联准确性,IDTP为正确分配数量,IDFN 为漏分配数量,IDFP为错误分配数量 | |
IDP↑ | 正确识别的计算检测的分数,评价跟踪器的好坏 | |
IDR↑ | 识别召回率,正确识别ground truth检测的分数 | |
ID_SW↓ | 目标身份交换的次数 |
Table 10
Evaluation of multi object detection competition results of VisDrone Challenge
方法 | AP | AP50 | AP75 | AR1 | AR10 | AR100 | AR500 | 年份 |
---|---|---|---|---|---|---|---|---|
HAL-Retina-Net | 31.88 | 46.18 | 32.12 | 0.97 | 7.50 | 34.43 | 90.63 | 2018 |
DPNet | 30.92 | 54.62 | 31.17 | 1.05 | 8.00 | 36.80 | 50.48 | |
DE-FPN | 27.10 | 48.72 | 26.58 | 0.90 | 6.97 | 33.58 | 40.57 | |
CFE-SSDv2 | 26.48 | 47.30 | 26.08 | 1.16 | 8.76 | 33.85 | 38.94 | |
RD4MS | 22.68 | 44.85 | 20.24 | 1.55 | 7.45 | 29.63 | 38.59 | |
DPNet-ensemble | 29.62 | 54.00 | 28.70 | 0.58 | 3.69 | 17.10 | 42.37 | 2019 |
RRNet | 29.13 | 55.82 | 27.23 | 1.02 | 8.50 | 35.19 | 46.05 | |
ACM-OD | 29.13 | 54.07 | 27.38 | 0.32 | 1.48 | 9.46 | 44.53 | |
S+D | 28.59 | 50.97 | 28.29 | 0.50 | 3.38 | 15.95 | 42.72 | |
BetterFPN | 28.55 | 53.63 | 26.68 | 0.86 | 7.56 | 33.81 | 44.02 | |
DroneEye2020 | 34.57 | 58.21 | 35.74 | 0.28 | 1.92 | 6.93 | 52.37 | 2020 |
TAUN | 34.54 | 59.42 | 34.97 | 0.14 | 0.72 | 12.81 | 49.8 | |
CDNet | 34.19 | 57.52 | 35.13 | 0.8 | 8.12 | 39.39 | 52.62 | |
CascadeAdapt | 34.16 | 58.42 | 34.5 | 0.84 | 8.17 | 39.96 | 47.86 | |
HR-Cascade++ | 32.47 | 55.06 | 33.34 | 0.94 | 7.81 | 37.93 | 50.65 | |
DBNet | 39.43 | 65.34 | 41.07 | 0.29 | 2.03 | 12.13 | 55.36 | 2021 |
SOLOer | 39.42 | 63.91 | 40.87 | 1.75 | 10.94 | 44.69 | 55.91 | |
Swin-T | 39.4 | 63.91 | 40.87 | 1.76 | 10.96 | 44.65 | 56.83 | |
TPH-YOLO V5 | 39.18 | 62.83 | 41.34 | 2.61 | 13.63 | 45.62 | 56.88 | |
VistrongerDet | 38.77 | 64.28 | 40.24 | 0.77 | 8.1 | 43.23 | 55.12 |
Table 11
Evaluation of multi object tracking competition results of VisDrone Challenge
方法 | AP | AP0.25 | AP0.50 | AP0.75 | APcar | APbus | APtrk | APped | APvan | 年份 |
---|---|---|---|---|---|---|---|---|---|---|
DBAI-Tracker | 43.94 | 57.32 | 45.18 | 29.32 | 55.13 | 44.97 | 42.73 | 31.01 | 45.85 | 2019 |
TrackKITSY | 39.19 | 48.83 | 39.36 | 29.37 | 54.92 | 29.05 | 34.19 | 36.57 | 41.2 | |
Flow-Tracker | 30.87 | 41.84 | 31 | 19.77 | 48.44 | 26.19 | 29.5 | 18.65 | 31.56 | |
HMTT | 28.67 | 39.05 | 27.88 | 19.08 | 44.35 | 30.56 | 18.75 | 26.49 | 23.19 | |
TNT_DRONE | 27.32 | 35.09 | 26.92 | 19.94 | 38.06 | 22.65 | 33.79 | 12.62 | 29.46 | |
COFE | 61.88 | 64.99 | 62 | 58.65 | 79.09 | 65.26 | 50.91 | 56.87 | 57.26 | 2020 |
SOMOT | 57.65 | 70.06 | 60.13 | 42.75 | 68.52 | 62.1 | 47.98 | 54.94 | 54.69 | |
PAS tracker | 50.8 | 62.24 | 50.74 | 39.43 | 62.59 | 50.59 | 42.18 | 44.34 | 54.3 | |
Deepsort | 42.11 | 58.82 | 42.64 | 24.86 | 55.06 | 43.18 | 41.3 | 29.1 | 41.88 | 2020 |
YOLO-TRAC | 42.1 | 52.94 | 41.86 | 31.49 | 52.81 | 48.98 | 39.17 | 28.92 | 40.59 | |
SOMOT | 58.61 | 70.75 | 61.26 | 43.84 | 69.18 | 63.46 | 48.45 | 55.64 | 56.34 | 2021 |
GIAOTracker-Fusion | 54.18 | 63.41 | 55.35 | 43.78 | 69.33 | 51.05 | 43.2 | 55.06 | 52.26 | |
MMDS | 52.68 | 62.92 | 53.42 | 41.69 | 70.2 | 40.68 | 51.94 | 50.27 | 50.29 | |
Deep IOU Tracker | 48.54 | 63.16 | 48.11 | 34.33 | 51.97 | 60.05 | 37.66 | 37.06 | 55.94 | |
YOLO-Deepsort -VisDrone | 46.7 | 57.43 | 48.92 | 33.75 | 60.32 | 43.61 | 36.22 | 40.73 | 52.62 |
1 | 李玺, 查宇飞, 张天柱, 等. 深度学习的目标跟踪算法综述[J]. 中国图象图形学报, 2019, 24(12): 2057-2080. |
LI X, ZHA Y F, ZHANG T Z, et al. Survey of visual object tracking algorithms based on deep learning[J]. Journal of Image and Graphics, 2019, 24(12): 2057-2080 (in Chinese). | |
2 | ELHOSENY M. Multi-object detection and tracking (MODT) machine learning model for real-time video surveillance systems[J]. Circuits, Systems, and Signal Processing, 2020, 39(2): 611-630. |
3 | 徐芳, 刘晶红, 孙辉, 等. 光学遥感图像海面船舶目标检测技术进展[J]. 光学 精密工程, 2021, 29(4): 916-931. |
XU F, LIU J H, SUN H, et al. Research progress on vessel detection using optical remote sensing image[J]. Optics and Precision Engineering, 2021, 29(4): 916-931 (in Chinese). | |
4 | 江波, 屈若锟, 李彦冬, 等. 基于深度学习的无人机航拍目标检测研究综述[J]. 航空学报, 2021, 42(4): 524519. |
JIANG B, QU R K, LI Y D, et al. Object detection in UAV imagery based on deep learning: Review[J]. Acta Aeronautica et Astronautica Sinica, 2021, 42(4): 524519 (in Chinese). | |
5 | AMMAR A, KOUBAA A, AHMED M, et al. Vehicle detection from aerial images using deep learning: A comparative study[J]. Electronics, 2021, 10(7): 820. |
6 | YAO H A, QIN R J, CHEN X Y. Unmanned aerial vehicle for remote sensing applications⁃a review[J]. Remote Sensing, 2019, 11(12): 1443. |
7 | RAVINDRAN R, SANTORA M J, JAMALI M M. Multi-object detection and tracking, based on DNN, for autonomous vehicles: A review[J]. IEEE Sensors Journal, 2021, 21(5): 5668-5677. |
8 | 葛宝义, 左宪章, 胡永江. 视觉目标跟踪方法研究综述[J]. 中国图象图形学报, 2018, 23(8): 1091-1107. |
GE B Y, ZUO X Z, HU Y J. Review of visual object tracking technology[J]. Journal of Image and Graphics, 2018, 23(8): 1091-1107 (in Chinese). | |
9 | BOURAYA S, BELANGOUR A. Approaches to video real time multi-object tracking and object detection: A survey[C]∥ 2021 12th International Symposium on Image and Signal Processing and Analysis (ISPA). Piscataway: IEEE Press, 2021: 145-151. |
10 | PAL S K, PRAMANIK A, MAITI J, et al. Deep learning in multi-object detection and tracking: State of the art[J]. Applied Intelligence, 2021, 51(9): 6400-6429. |
11 | CIAPARRONE G, LUQUE SÁNCHEZ F, TABIK S, et al. Deep learning in video multi-object tracking: A survey[J]. Neurocomputing, 2020, 381: 61-88. |
12 | RANGESH A, TRIVEDI M M. No blind spots: Full-surround multi-object tracking for autonomous vehicles using cameras and LiDARs[J]. IEEE Transactions on Intelligent Vehicles, 2019, 4(4): 588-599. |
13 | GIRSHICK R, DONAHUE J, DARRELL T, et al. Rich feature hierarchies for accurate object detection and semantic segmentation[C]∥ 2014 IEEE Conference on Computer Vision and Pattern Recognition. Piscataway: IEEE Press, 2014: 580-587. |
14 | GIRSHICK R. Fast R-CNN[C]∥ 2015 IEEE International Conference on Computer Vision (ICCV). Piscataway: IEEE Press, 2016: 1440-1448. |
15 | REN S Q, HE K M, GIRSHICK R, et al. Faster R-CNN: Towards real-time object detection with region proposal networks[J]. IEEE Transactions on Pattern Analysis and Machine Intelligence, 2017, 39(6): 1137-1149. |
16 | CAI Z W, VASCONCELOS N. Cascade R-CNN: delving into high quality object detection[C]∥ 2018 IEEE/CVF Conference on Computer Vision and Pattern Recognition. Piscataway: IEEE Press, 2018: 6154-6162. |
17 | LIU W, ANGUELOV D, ERHAN D, et al. SSD: Single shot MultiBox detector[C]∥European Conference on Computer Vision. Cham: Springer, 2016: 21-37. |
18 | REDMON J, DIVVALA S, GIRSHICK R, et al. You only look once: Unified, real-time object detection[C]∥2016 IEEE Conference on Computer Vision and Pattern Recognition (CVPR). Piscataway: IEEE Press, 2016: 779-788. |
19 | REDMON J, FARHADI A. YOLO9000: Better, faster, stronger[C]∥ 2017 IEEE Conference on Computer Vision and Pattern Recognition (CVPR). Piscataway: IEEE Press, 2017: 6517-6525. |
20 | REDMON J, FARHADI A. YOLOv3: An incremental improvement[DB/OL]. arXiv preprint: 1804.02767, 2018. |
21 | BOCHKOVSKIY A, WANG C Y, LIAO H Y M. YOLOv4: Optimal speed and accuracy of object detection[DB/OL]. arXiv preprint: 2004.10934, 2020. |
22 | WANG C Y, BOCHKOVSKIY A, LIAO H Y M. YOLOv7: Trainable bag-of-freebies sets new state-of-the-art for real-time object detectors[DB/OL]. arXiv preprint:2207.02696, 2022. |
23 | DUAN K W, BAI S, XIE L X, et al. CenterNet: Keypoint triplets for object detection[C]∥ 2019 IEEE/CVF International Conference on Computer Vision (ICCV). Piscataway: IEEE Press, 2020: 6568-6577. |
24 | WU X, LI W, HONG D F, et al. Deep learning for unmanned aerial vehicle-based object detection and tracking: A survey[J]. IEEE Geoscience and Remote Sensing Magazine, 2022, 10(1): 91-124. |
25 | OSCO L P, MARCATO J Jr, MARQUES RAMOS A P, et al. A review on deep learning in UAV remote sensing[J]. International Journal of Applied Earth Observation and Geoinformation, 2021, 102: 102456. |
26 | SRIVASTAVA S, NARAYAN S, MITTAL S. A survey of deep learning techniques for vehicle detection from UAV images[J]. Journal of Systems Architecture, 2021, 117: 102152. |
27 | CAZZATO D, CIMARELLI C, SANCHEZ-LOPEZ J L, et al. A survey of computer vision methods for 2D object detection from unmanned aerial vehicles[J]. Journal of Imaging, 2020, 6(8): 78. |
28 | 陈琳, 刘允刚. 面向无人机的视觉目标跟踪算法:综述与展望[J]. 信息与控制, 2022, 51(1): 23-40. |
CHEN L, LIU Y G. UAV visual target tracking algorithms: Review and future prospect[J]. Information and Control, 2022, 51(1): 23-40 (in Chinese). | |
29 | AYALEW A, POOJA. A review on object detection from Unmanned Aerial Vehicle using CNN[J]. International Journal of Advance Research, Ideas and Innovations in Technology, 2019, 5: 241-243. |
30 | VIOLA P, JONES M. Rapid object detection using a boosted cascade of simple features[C]∥ Proceedings of the 2001 IEEE Computer Society Conference on Computer Vision and Pattern Recognition. Piscataway: IEEE Press, 2003. |
31 | DALAL N, TRIGGS B. Histograms of oriented gradients for human detection[C]∥ 2005 IEEE Computer Society Conference on Computer Vision and Pattern Recognition (CVPR’05). Piscataway: IEEE Press, 2005: 886-893. |
32 | FELZENSZWALB P, MCALLESTER D, RAMANAN D. A discriminatively trained, multiscale, deformable part model[C]∥ 2008 IEEE Conference on Computer Vision and Pattern Recognition. Piscataway: IEEE Press, 2008: 1-8. |
33 | ABUGHALIEH K M, SABABHA B H, RAWASHDEH N A. A video-based object detection and tracking system for weight sensitive UAVs[J]. Multimedia Tools and Applications, 2019, 78(7): 9149-9167. |
34 | BAYKARA H C, B 1Y1K E, GÜL G,et al. Real-time detection, tracking and classification of multiple moving objects in UAV videos[C]∥ 2017 IEEE 29th International Conference on Tools with Artificial Intelligence (ICTAI). Piscataway: IEEE Press, 2018: 945-950. |
35 | JIANG X L, CAO X B. Surveillance from above: A detection-and-prediction based multiple target tracking method on aerial videos[C]∥ 2016 Integrated Communications Navigation and Surveillance (ICNS). Piscataway: IEEE Press, 2016: 4D2-1. |
36 | AVOLA D, CINQUE L, DIKO A, et al. MS-Faster RCNN: Multi-stream backbone for improved Faster RCNN object detection and aerial tracking from UAV images[J]. Remote Sensing, 2021, 13(9): 1670. |
37 | STADLER D. Multi-object tracking in drone videos[C]∥2020 Joint Workshop of Fraunhofer IOSB and Institute for Anthropomatics, Vision and Fusion Laboratory, 2021: 123-133. |
38 | HUANG W, ZHOU X S, DONG M C, et al. Multiple objects tracking in the UAV system based on hierarchical deep high-resolution network[J]. Multimedia Tools and Applications, 2021, 80(9): 13911-13929. |
39 | ZHANG S Y, ZHUO L, ZHANG H, et al. Object tracking in unmanned aerial vehicle videos via multifeature discrimination and instance-aware attention network[J]. Remote Sensing, 2020, 12(16): 2646. |
40 | LIU Z M, GAO G Y, SUN L, et al. HRDNet: High-resolution detection network for small objects[C]∥ 2021 IEEE International Conference on Multimedia and Expo (ICME). Piscataway: IEEE Press, 2021: 1-6. |
41 | LIU Y J, YANG F B, HU P. Small-object detection in UAV-captured images via multi-branch parallel feature pyramid networks[J]. IEEE Access, 2020, 8: 145740-145750. |
42 | AZIMI S M, KRAUS M, BAHMANYAR R, et al. Multiple pedestrians and vehicles tracking in aerial imagery using a convolutional neural network[J]. Remote Sensing, 2021, 13(10): 1953. |
43 | DU Y H, WAN J F, ZHAO Y Y, et al. GIAOTracker: A comprehensive framework for MCMOT with global information and optimizing strategies in VisDrone 2021[C]∥ 2021 IEEE/CVF International Conference on Computer Vision Workshops (ICCVW). Piscataway: IEEE Press, 2021: 2809-2819. |
44 | TØTTRUP D, SKOVGAARD S L, LE FEVRE SEJERSEN J, et al. A fast and accurate approach to multiple-vehicle localization and tracking from monocular aerial images[J]. Journal of Imaging, 2021, 7(12): 270. |
45 | ALBABA B M, OZER S. SyNet: An ensemble network for object detection in UAV images[C]∥ 2020 25th International Conference on Pattern Recognition (ICPR). Piscataway: IEEE Press, 2021: 10227-10234. |
46 | CAO J L, CHOLAKKAL H, ANWER R M, et al. D2Det: Towards high quality object detection and instance segmentation[C]∥ 2020 IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR). Piscataway: IEEE Press, 2020: 11482-11491. |
47 | YANG F, FAN H, CHU P, et al. Clustered object detection in aerial images[C]∥ 2019 IEEE/CVF International Conference on Computer Vision (ICCV). Piscataway: IEEE Press, 2020: 8310-8319. |
48 | ZHANG R Q, SHAO Z F, HUANG X A, et al. Object detection in UAV images via global density fused convolutional network[J]. Remote Sensing, 2020, 12(19): 3140. |
49 | YU W P, YANG T, CHEN C. Towards resolving the challenge of long-tail distribution in UAV images for object detection[C]∥ 2021 IEEE Winter Conference on Applications of Computer Vision (WACV). Piscataway: IEEE Press, 2021: 3257-3266. |
50 | ZHANG X D, IZQUIERDO E, CHANDRAMOULI K. Dense and small object detection in UAV vision based on cascade network[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 118-126. |
51 | YANG J X, XIE X M, YANG W Z. Effective contexts for UAV vehicle detection[J]. IEEE Access, 2019, 7: 85042-85054. |
52 | WU Z Y, SURESH K, NARAYANAN P, et al. Delving into robust object detection from unmanned aerial vehicles: A deep nuisance disentanglement approach[C]∥ 2019 IEEE/CVF International Conference on Computer Vision (ICCV). Piscataway: IEEE Press, 2020: 1201-1210. |
53 | ZHANG W, LIU C S, CHANG F L, et al. Multi-scale and occlusion aware network for vehicle detection and segmentation on UAV aerial images[J]. Remote Sensing, 2020, 12(11): 1760. |
54 | CHEN C R, ZHANG Y, LV Q X, et al. RRNet: A hybrid detector for object detection in drone-captured images[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 100-108. |
55 | WANG H R, WANG Z X, JIA M X, et al. Spatial attention for multi-scale feature refinement for object detection[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 64-72. |
56 | TANG Z Y, LIU X, YANG B J. PENet: Object detection using points estimation in high definition aerial images[C]∥ 2020 19th IEEE International Conference on Machine Learning and Applications (ICMLA). Piscataway: IEEE Press, 2021: 392-398. |
57 | DIKE H U, ZHOU Y M. A robust quadruplet and faster region-based CNN for UAV video-based multiple object tracking in crowded environment[J]. Electronics, 2021, 10(7): 795. |
58 | LIN Q Z, DING Y, XU H, et al. ECascade-RCNN: Enhanced cascade RCNN for multi-scale object detection in UAV images[C]∥ 2021 7th International Conference on Automation, Robotics and Applications (ICARA). Piscataway: IEEE Press, 2021: 268-272. |
59 | YOUSSEF Y, ELSHENAWY M. Automatic vehicle counting and tracking in aerial video feeds using cascade region-based convolutional neural networks and feature pyramid networks[J]. Transportation Research Record: Journal of the Transportation Research Board, 2021, 2675(8): 304-317. |
60 | LEE Y, LEE S H, YOO J, et al. Efficient single-shot multi-object tracking for vehicles in traffic scenarios[J]. Sensors, 2021, 21(19): 6358. |
61 | MAKAROV S B, PAVLOV V A, BEZBORODOV A K, et al. Multiple object tracking using convolutional neural network on aerial imagery sequences[M]∥ Springer Proceedings in Physics. Cham: Springer International Publishing, 2020: 413-420. |
62 | HOSSAIN S, LEE D J. Deep learning-based real-time multiple-object detection and tracking from aerial imagery via a flying robot with GPU-based embedded devices[J]. Sensors, 2019, 19(15): 3371. |
63 | LI J, CHEN S, ZHANG F B, et al. An adaptive framework for multi-vehicle ground speed estimation in airborne videos[J]. Remote Sensing, 2019, 11(10): 1241. |
64 | EMIYAH C, NYARKO K, CHAVIS C, et al. Extracting vehicle track information from unstabilized drone aerial videos using YOLOv4 common object detector and computer vision[C]∥ Proceedings of the Future Technologies Conference. Cham: Springer, 2022: 232-239. |
65 | YANG T, LI D D, BAI Y, et al. Multiple-object-tracking algorithm based on dense trajectory voting in aerial videos[J]. Remote Sensing, 2019, 11(19): 2278. |
66 | LIU M J, WANG X H, ZHOU A J, et al. UAV-YOLO: Small object detection on unmanned aerial vehicle perspective[J]. Sensors, 2020, 20(8): 2238. |
67 | NING M, MA X L, LU Y, et al. SeeFar: Vehicle speed estimation and flow analysis from a moving UAV[C]∥ International Conference on Image Analysis and Processing. Cham: Springer, 2022: 278-289. |
68 | KAPANIA S, SAINI D, GOYAL S, et al. Multi object tracking with UAVs using deep SORT and YOLOv3 RetinaNet detection framework[C]∥ Proceedings of the 1st ACM Workshop on Autonomous and Intelligent Mobile Systems. New York: ACM, 2020: 1-6. |
69 | TIAN G Y, LIU J R, YANG W Y. A dual neural network for object detection in UAV images[J]. Neurocomputing, 2021, 443: 292-301. |
70 | ZHANG P Y, ZHONG Y X, LI X Q. SlimYOLOv3: Narrower, faster and better for real-time UAV applications[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 37-45. |
71 | 刘芳, 浦昭辉, 张帅超. 基于注意力特征融合的无人机多目标跟踪算法[J]. 控制与决策, 2023, 38(2): 345-353. |
LIU F, PU Z H, ZHANG S C. UAV multi-target tracking algorithm based on attention feature fusion[J]. Control and Decision, 2023, 38(2): 345-353 (in Chinese). | |
72 | SAETCHNIKOV I, SKAKUN V, TCHERNIAVSKAIA E. Efficient objects tracking from an unmanned aerial vehicle[C]∥ 2021 IEEE 8th International Workshop on Metrology for AeroSpace (MetroAeroSpace). Piscataway: IEEE Press, 2021: 221-225. |
73 | LI Z K, LIU X L, ZHAO Y, et al. A lightweight multi-scale aggregated model for detecting aerial images captured by UAVs[J]. Journal of Visual Communication and Image Representation, 2021, 77: 103058. |
74 | LIANG X, ZHANG J, ZHUO L, et al. Small object detection in unmanned aerial vehicle images using feature fusion and scaling-based single shot detector with spatial context analysis[J]. IEEE Transactions on Circuits and Systems for Video Technology, 2020, 30(6): 1758-1770. |
75 | WANG X R, LI W H, GUO W, et al. SPB-YOLO: An efficient real-time detector for unmanned aerial vehicle images[C]∥ 2021 International Conference on Artificial Intelligence in Information and Communication (ICAIIC). Piscataway: IEEE Press, 2021: 099-104. |
76 | LIU Y Z, DING Z M, CAO Y, et al. Multi-scale feature fusion UAV image object detection method based on dilated convolution and attention mechanism[C]∥ Proceedings of the 2020 8th International Conference on Information Technology: IoT and Smart City. New York: ACM, 2020: 125-132. |
77 | ZHANG Z Y, LIU Y P, LIU T C, et al. DAGN: A real-time UAV remote sensing image vehicle detection framework[J]. IEEE Geoscience and Remote Sensing Letters, 2020, 17(11): 1884-1888. |
78 | JADHAV A, MUKHERJEE P, KAUSHIK V, et al. Aerial multi-object tracking by detection using deep association networks[C]∥ 2020 National Conference on Communications (NCC). Piscataway: IEEE Press, 2020: 1-6. |
79 | PI Z L, LIAN Y C, CHEN X E, et al. A novel spatial and temporal context-aware approach for drone-based video object detection[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 179-188. |
80 | LIANG Z Q, WANG J S, XIAO G, et al. FAANet: Feature-aligned attention network for real-time multiple object tracking in UAV videos[J]. Chinese Optics Letters, 2022, 20(8): 081101. |
81 | ZHANG H T, WANG G A, LEI Z C, et al. Eye in the sky: Drone-based object tracking and 3D localization[C]∥ Proceedings of the 27th ACM International Conference on Multimedia. New York: ACM, 2019: 899-907. |
82 | WU Q T, ZHOU Y M. Real-time object detection based on unmanned aerial vehicle[C]∥ 2019 IEEE 8th Data Driven Control and Learning Systems Conference (DDCLS). Piscataway: IEEE Press, 2019: 574-579. |
83 | KYRKOU C, PLASTIRAS G, THEOCHARIDES T, et al. DroNet: Efficient convolutional neural network detector for real-time UAV applications[C]∥ 2018 Design, Automation & Test in Europe Conference & Exhibition (DATE). Piscataway: IEEE Press, 2018: 967-972. |
84 | BALAMURALIDHAR N, TILON S, NEX F. MultEYE: Monitoring system for real-time vehicle detection, tracking and speed estimation from UAV imagery on edge-computing platforms[J]. Remote Sensing, 2021, 13(4): 573. |
85 | LI M L, ZHAO X K, LI J S, et al. ComNet: Combinational neural network for object detection in UAV-borne thermal images[J]. IEEE Transactions on Geoscience and Remote Sensing, 2021, 59(8): 6662-6673. |
86 | ZHANG J, LIANG X, WANG M, et al. Coarse-to-fine object detection in unmanned aerial vehicle imagery using lightweight convolutional neural network and deep motion saliency[J]. Neurocomputing, 2020, 398: 555-565. |
87 | WU P P, XU H, DING Y, et al. An improved online multiple object tracking algorithm based on KFHT motion compensation model in the aerial videos[C]∥ Proc SPIE 11763, Seventh Symposium on Novel Photoelectronic Detection Technology and Applications, 2021, 11763: 2431-2436. |
88 | AL-SHAKARJI N M, BUNYAK F, SEETHARAMAN G, et al. Multi-object tracking cascade with multi-step data association and occlusion handling[C]∥ 2018 15th IEEE International Conference on Advanced Video and Signal Based Surveillance (AVSS). Piscataway: IEEE Press, 2019: 1-6. |
89 | WANG J E, SIMEONOVA S, SHAHBAZI M. Orientation- and scale-invariant multi-vehicle detection and tracking from unmanned aerial videos[J]. Remote Sensing, 2019, 11(18): 2155. |
90 | YU H Y, LI G R, ZHANG W G, et al. Self-balance motion and appearance model for multi-object tracking in UAV[C]∥ Proceedings of the ACM Multimedia Asia. New York: ACM, 2019: 1-6. |
91 | AHN H, CHO H J. Research of multi-object detection and tracking using machine learning based on knowledge for video surveillance system[J]. Personal and Ubiquitous Computing, 2022, 26(2): 385-394. |
92 | LUSK P C, BEARD R W. Visual multiple target tracking from a descending aerial platform[C]∥ 2018 Annual American Control Conference (ACC). Piscataway: IEEE Press, 2018: 5088-5093. |
93 | LI W Q, MU J T, LIU G Z. Multiple object tracking with motion and appearance cues[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 161-169. |
94 | ARDÖ H, NILSSON M. Multi target tracking from drones by learning from generalized graph differences[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 46-54. |
95 | FU H Y, GUAN J, JING F, et al. A real-time multi-vehicle tracking framework in intelligent vehicular networks[J]. China Communications, 2021, 18(6): 89-99. |
96 | HE Y J, FU C H, LIN F L, et al. Towards robust visual tracking for unmanned aerial vehicle with tri-attentional correlation filters[C]∥ 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). Piscataway: IEEE Press, 2021: 1575-1582. |
97 | STADLER D, SOMMER L W, BEYERER J. PAS tracker: Position-, appearance- and size-aware multi-object tracking in drone videos[C]∥ European Conference on Computer Vision. Cham: Springer, 2020: 604-620. |
98 | LI F, FU C H, LIN F L, et al. Training-set distillation for real-time UAV object tracking[C]∥ 2020 IEEE International Conference on Robotics and Automation (ICRA). Piscataway: IEEE Press, 2020: 9715-9721. |
99 | LI Y M, FU C H, HUANG Z Y, et al. Intermittent contextual learning for keyfilter-aware UAV object tracking using deep convolutional feature[J]. IEEE Transactions on Multimedia, 2021, 23: 810-822. |
100 | XU S Y, SAVVARIS A, HE S M, et al. Real-time implementation of YOLO JPDA for small scale UAV multiple object tracking[C]∥ 2018 International Conference on Unmanned Aircraft Systems (ICUAS). Piscataway: IEEE Press, 2018: 1336-1341. |
101 | LEE M H, YEOM S. Tracking of moving vehicles with a UAV[C]∥ 2018 Joint 10th International Conference on Soft Computing and Intelligent Systems (SCIS) and 19th International Symposium on Advanced Intelligent Systems (ISIS). Piscataway: IEEE Press, 2019: 928-931. |
102 | 王旭辰, 韩煜祺, 唐林波, 等. 基于深度学习的无人机载平台多目标检测和跟踪算法研究[J]. 信号处理, 2022, 38(1): 157-163. |
WANG X C, HAN Y Q, TANG L B, et al. Multi target detection and tracking algorithm for UAV platform based on deep learning[J]. Journal of Signal Processing, 2022, 38(1): 157-163 (in Chinese). | |
103 | LUO X, ZHAO R, GAO X A. Research on UAV multi-object tracking based on deep learning[C]∥ 2021 IEEE International Conference on Networking, Sensing and Control (ICNSC). Piscataway: IEEE Press, 2021. |
104 | KHALKHALI M B, VAHEDIAN A, YAZDI H S. Situation assessment-augmented interactive Kalman filter for multi-vehicle tracking[J]. IEEE Transactions on Intelligent Transportation Systems, 2022, 23(4): 3766-3776. |
105 | WOJKE N, BEWLEY A, PAULUS D. Simple online and realtime tracking with a deep association metric[C]∥ 2017 IEEE International Conference on Image Processing (ICIP). Piscataway: IEEE Press, 2018: 3645-3649. |
106 | WU Y, WANG Y, ZHANG D, et al. Research on vehicle tracking method based on UAV video[C]∥ 2nd International Conference on Internet of Things and Smart City (IoTSC 2022). SPIE, 2022: 801-806. |
107 | WU H, DU C J, JI Z P, et al. SORT-YM: An algorithm of multi-object tracking with YOLOv4-tiny and motion prediction[J]. Electronics, 2021, 10(18): 2319. |
108 | CHEN T, PENNISI A, LI Z, et al. A hierarchical association framework for multi-object tracking in airborne videos[J]. Remote Sensing, 2018, 10(9): 1347. |
109 | YU H Y, LI G R, SU L, et al. Conditional GAN based individual and global motion fusion for multiple object tracking in UAV videos[J]. Pattern Recognition Letters, 2020, 131: 219-226. |
110 | PAN S Y, TONG Z H, ZHAO Y Y, et al. Multi-object tracking hierarchically in visual data taken from drones[C]∥ 2019 IEEE/CVF International Conference on Computer Vision Workshop (ICCVW). Piscataway: IEEE Press, 2020: 135-143. |
111 | BAHMANYAR R, AZIMI S M, REINARTZ P. Multiple vehicles and people tracking in aerial imagery using stack of micro single-object-tracking CNNs[J]. The International Archives of the Photogrammetry, Remote Sensing and Spatial Information Sciences, 2019, XLII-4/W18: 163-170. |
112 | MARVASTI-ZADEH S M, KHAGHANI J, GHANEI-YAKHDAN H, et al. COMET: Context-aware IoU-guided network for small object tracking[C]∥ Asian Conference on Computer Vision. Cham: Springer, 2021: 594-611. |
113 | ROBICQUET A, SADEGHIAN A, ALAHI A, et al. Learning social etiquette: Human trajectory understanding in crowded scenes[C]∥ European Conference on Computer Vision. Cham: Springer, 2016: 549-565. |
114 | DU D W, QI Y K, YU H Y, et al. The unmanned aerial vehicle benchmark: Object detection and tracking[C]∥European Conference on Computer Vision. Cham: Springer, 2018: 375-391. |
115 | ZHU P, WEN L, BIAN X, et al. Vision meets drones: A challenge [DB/OL]. arXiv preprint: 1804.07437, 2018. |
116 | ZHU P F, WEN L Y, DU D W, et al. Vision meets drones: past, present and future[DB/OL] arXiv preprint: 2001.06303, 2020. |
117 | BONDI E, JAIN R, AGGRAWAL P, et al. BIRDSAI: A dataset for detection and tracking in aerial thermal infrared videos[C]∥ 2020 IEEE Winter Conference on Applications of Computer Vision (WACV). Piscataway: IEEE Press, 2020: 1736-1745. |
118 | HSIEH M R, LIN Y L, HSU W H. Drone-based object counting by spatially regularized regional proposal network[C]∥ 2017 IEEE International Conference on Computer Vision (ICCV). Piscataway: IEEE Press, 2017: 4165-4173. |
119 | XU X W, ZHANG X Y, YU B, et al. DAC-SDC low power object detection challenge for UAV applications[J]. IEEE Transactions on Pattern Analysis and Machine Intelligence, 2021, 43(2): 392-403. |
120 | MANDAL M, KUMAR L K, VIPPARTHI S K. MOR-UAV: A benchmark dataset and baselines for moving object recognition in UAV videos[C]∥ Proceedings of the 28th ACM International Conference on Multimedia. New York: ACM, 2020: 2626-2635. |
121 | ZHU P F, SUN Y M, WEN L Y, et al. Drone based RGBT vehicle detection and counting: A challenge[DB/OL]. arXiv preprint: 2003.02437, 2020. |
122 | BOZCAN I, KAYACAN E. AU-AIR: A multi-modal unmanned aerial vehicle dataset for low altitude traffic surveillance[C]∥ 2020 IEEE International Conference on Robotics and Automation (ICRA). Piscataway: IEEE Press, 2020: 8504-8510. |
123 | ZHANG H J, SUN M S, LI Q, et al. An empirical study of multi-scale object detection in high resolution UAV images[J]. Neurocomputing, 2021, 421: 173-182. |
124 | BERNARDIN K, STIEFELHAGEN R. Evaluating multiple object tracking performance: The CLEAR MOT metrics[J]. Journal on Image and Video Processing, 2008, 2008Article No. 1, |
125 | RISTANI E, SOLERA F, ZOU R, et al. Performance measures and a data set for multi-target, multi-camera tracking[C]∥ European Conference on Computer Vision. Cham: Springer, 2016: 17-35. |
126 | LUITEN J, OS̆EP A, DENDORFER P, et al. HOTA: A higher order metric for evaluating multi-object tracking[J]. International Journal of Computer Vision, 2021, 129(2): 548-578. |
[1] | Jiaqi LIU, Rongqian CHEN, Jinhua LOU, Xu HAN, Hao WU, Yancheng YOU. Aerodynamic shape optimization of high-speed helicopter rotor airfoil based on deep learning [J]. Acta Aeronautica et Astronautica Sinica, 2024, 45(9): 529828-529828. |
[2] | Xudong LUO, Yiquan WU, Jinlin CHEN. Research progress on deep learning methods for object detection and semantic segmentation in UAV aerial images [J]. Acta Aeronautica et Astronautica Sinica, 2024, 45(6): 28822-028822. |
[3] | Haiqiao LIU, Meng LIU, Zichao GONG, Jing DONG. A review of image matching methods based on deep learning [J]. Acta Aeronautica et Astronautica Sinica, 2024, 45(3): 28796-028796. |
[4] | Xin SU, Runcheng GUAN, Qiao WANG, Weizheng YUAN, Xianglian LYU, Yang HE. Ice area and thickness detection method based on deep learning [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(S2): 729283-729283. |
[5] | Liqun CHEN, Xu ZOU, Lei ZHANG, Yingpan ZHU, Gang WANG, Jinyong CHEN. On⁃board intelligent target detection technology based on domestic commercial components [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(S2): 728860-728860. |
[6] | Pengyu LIU, Xueyao ZHU. Semantic parsing technology of air traffic control instruction in fusion airspace based on deep learning [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(S1): 727592-727592. |
[7] | Lei HE, Weiqi QIAN, Kangsheng DONG, Xian YI, Congcong CHAI. Aerodynamic characteristics modeling of iced airfoil based on convolution neural networks [J]. ACTA AERONAUTICAET ASTRONAUTICA SINICA, 2023, 44(5): 126434-126434. |
[8] | Peng DING, Yafei SONG. A cost-sensitive method for aerial target intention recognition [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(24): 328551-328551. |
[9] | Xiaohang LI, Jianjiang ZHOU. Multi⁃scale modality fusion network based on adaptive memory length [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(22): 628977-628977. |
[10] | Haowen LUO, Shaoming HE, Tianyu JIN, Zichao LIU. Impact-angle-constrained with time-minimum guidance algorithm based on transfer learning [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(19): 328400-328400. |
[11] | Yunhe ZHAO, Shengnan WANG. Solution to stress intensity factor by weight function method based on deep learning [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(19): 228367-228367. |
[12] | Shuyi GAO, Defu LIN, Duo ZHENG, Xinyu HU. Intelligent cooperative interception strategy of aircraft against cluster attack [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(18): 328301-328301. |
[13] | Rongsheng ZHANG, Yansheng WU, Xudong QIN, Puzhuo ZHANG. A real⁃time in⁃flight wind estimation and prediction method based on deep learning [J]. Acta Aeronautica et Astronautica Sinica, 2023, 44(13): 327860-327860. |
[14] | Qiang WANG, Letian WU, Yong WANG, Huan WANG, Wankou YANG. An infrared small target detection method based on key point [J]. ACTA AERONAUTICAET ASTRONAUTICA SINICA, 2023, 44(10): 328173-328173. |
[15] | SU Lingfei, HUA Yongzhao, DONG Xiwang, REN Zhang. Human-UAV swarm multi-modal intelligent interaction methods [J]. ACTA AERONAUTICAET ASTRONAUTICA SINICA, 2022, 43(S1): 727001-727001. |
Viewed | ||||||
Full text |
|
|||||
Abstract |
|
|||||
Address: No.238, Baiyan Buiding, Beisihuan Zhonglu Road, Haidian District, Beijing, China
Postal code : 100083
E-mail:hkxb@buaa.edu.cn
Total visits: 6658907 Today visits: 1341All copyright © editorial office of Chinese Journal of Aeronautics
All copyright © editorial office of Chinese Journal of Aeronautics
Total visits: 6658907 Today visits: 1341