基于RDK X5的智慧交通监控系统
一、项目背景
在当前高等教育普及化、大学持续扩招的宏观背景下,众多高校的在校学生规模日益庞大。伴随而来的是学生外出活动、外卖服务需求激增,以及家长探访频率的提升,这些因素共同促使校外车辆入校频次与学生自有机动车、非机动车数量急剧上升。这一系列变化不仅加剧了校园交通流量,还引发了一系列交通不文明行为的频发,具体表现为:车辆在校园内超速行驶、漂移炫技、违规停放,以及忽视行人优先权;学生自行车随意停放,频繁侵占机动车道及人行道,严重阻碍了校园内的正常交通秩序与安全通行。
鉴于上述严峻的交通管理挑战,本项目应运而生,其核心目标在于设计并实施一套依托深度学习技术的智能化互联网交通监测系统。该系统将创新性地采用国产高端AI开发板RDK X5作为核心硬件支撑平台,旨在精准高效地应对由电动车限行政策调整及外来车辆管理开放所带来的复杂交通管理难题。通过此项目的实施,我们期望能够有效提升校园交通管理的智能化水平,促进交通文明行为的养成,保障师生安全便捷的校园出行环境。
二、项目内容
基于深度学习算法和先进的图像处理技术,本系统将实现对校内各类机动车和非机动车的精准检测与识别,以实现对校内车辆实现精准溯源,具体功能包括:
2.1 车辆检测与车牌识别
(1)车辆分类识别: 利用深度学习算法训练模型,对校园内的车辆类型(如电动车、摩托车、轿车等)进行分类识别。
(2)车牌自动识别: 通过OCR(光学字符识别)技术,自动捕捉并识别机动车车牌号,并与学校数据库实时匹配,确定车辆身份和性质,包括区分是否为外卖车、网约车、临时外来车辆,或是未在校内登记备案的车辆。
(3)车流量记录与分析: 系统将实时记录各监测区域的车流量变化情况,为校内交通流量统计分析提供数据支持。该数据将定期存储至服务器中,便于校方分析车流趋势,为政策制定和车辆流量调控提供科学依据。
2.2 违规行为智能检测
系统通过高精度摄像头和多种传感器采集校园内的交通行为数据,结合深度学习算法根据国家道路交通法以及各大学校区或小型公有区域交通管理条例进行交通行为综合判定以实现以下功能:
(1)超速检测与实时提醒: 利用摄像头捕捉行驶中的机动车,通过检测行驶轨迹和时间间隔计算出速度。若检测到车辆超过校园限速,系统将自动记录相关数据并实时发送提醒,以抑制超速行驶行为。
(2)违停行为识别: 算法将自动识别机动车与非机动车在禁停区域内的违规停放行为,若检测到违停超过规定时间,系统将自动拍摄留证,并将违规信息上传至监控平台。
(3)礼让行人行为识别: 基于目标检测和行为识别模型,系统将识别机动车在校内是否有礼让行人行为。如有未礼让行人行为出现,系统将记录并提醒,助力打造文明交通环境。
(4)数据记录与违章档案生成: 系统自动将各类违章行为的数据存储,形成相应的违章档案,供校方进一步追踪和管理违规行为。
2.3 智能网联系统与在线监测平台
为了确保校园交通管理的实时性与便捷性,本系统基于RDK X5设计了一个智能网联系统,并提供可视化GUI以及智能分析在线监测平台的功能:
(1)违规行为自动上报: 当检测到违规行为后,系统通过互联网将违规信息(如违停照片、车辆识别信息、违章行为类型等)自动上传至在线监测平台,供校内安保、交通管理部门实时查看和跟踪。
(2)交通状况实时监控: 监测平台将自动生成全校车流量数据监控地图,并根据不同时段动态显示各区域交通流量情况,有助于及时发现和缓解交通拥堵点。
(3)智能通知功能: 当校园某一位置交通流量过高或存在频繁违规行为时,系统可向管理人员发送提醒,便于校方采取针对性管控措施。
2.4 系统集成与边缘化部署
本项目将通过边缘计算技术,将所有算法集成部署至国产高端AI开发板RDK X5,实现实时监控和数据处理,提升系统反应速度和计算效率:
(1)边缘计算部署: 通过将数据处理任务分布在边缘节点设备上,使得交通数据能够在本地设备中快速计算,减少数据上传延迟,提高系统的实时性和智能化程度,减少服务器机房设备的投入。
(2)深度学习算力支持: RDK X5开发板提供强大的算力支持,确保深度学习算法的高效运行,实现对车辆、行人等目标的实时识别、分析及处理。
(3)可扩展性设计: 系统将预留接口和API,便于未来接入更多监控设备或功能模块,支持校园交通管理的不断升级与优化。
三、开发介绍
3.1 车辆识别模型训练
我们要实现一个智能互联网交通检测系统重中之重肯定是实现系统对车辆的识别与检测,首先我在实验室外面的阳台上用三脚架和不用的手机对校道的进行不间断拍摄用于创建真实环境下的交通数据集
同时我上网寻找了一部分交通摄像头拍摄的路口车辆数据集UA-DETRAC,两者按照比例构建成了我们最终的数据集,接着使用labeling对数据集进行漫长的标记, 标记完后便可使用yolov5-2.0进行训练,训练过程省略...(一万字)...
3.2 模型量化与部署
3.2.1 安装官方DockerOE包
· 地平线OE配套下载的GPU/CPU的Docker镜像.tar.gz如何使用?
要想调用RDK X5的10TOPS的算力需要对我们训练出来的pt模型进行转化,类似于在Jetson中使用TensorRT对模型进行加速,我们也需要将我们训练得到的模型量化为可以在BPU上面运行的架构,这个时候就需要用到地瓜官方提供给我们的OE转换包啦,具体的链接附在了上面,我们首先安装Docker:Docker: Accelerated Container Application Development选择好对应的版本安装即可
· 具体安装教程可以参考这个教程:【Docker】Windows11操作系统下安装、使用Docker保姆级教程_docker windo11_win11 安装docker-CSDN博客
· 以及如何将Docker安装至其他盘:Windows11 安装Docker,安装至D盘(其他非C盘皆可)_docker安装到d盘-CSDN博客
安装完Docker以及官方的OE包后即可开始对我们的模型进行量化
首先我们使用yolov5代码里面自带的export.py将我们生成的.pt模型转换为.onnx的模型
!!!注意!!!
我们需要修改输出头,确保为4维的NHWC输出 修改./models/yolo.py文件, Detect类, forward方法, 约22行. 注:建议保留好原本的forward方法,例如改一个其他的名字forward_, 方便在训练的时候换回来
def forward(self, x): return [self.m[i](x[i]).permute(0,2,3,1).contiguous() for i in range(self.nl)]
具体步骤不清楚的可以参考Model Zoo的教程YOLOv5 Detect
接着我们对模型进行量化,参考天工开物工具链手册和OE包, 对模型进行检查, 所有算子均在BPU上, 之后按照提示对YAML文件(对应的yaml文件在./ptq_yamls
目录下.)进行修改然后编译即可.
(bpu_docker) $ hb_mapper checker --model-type onnx --march bayes-e --model Car_Detect.onnx
(bpu_docker) $ hb_mapper makertbin --model-type onnx --config yolov5_detect_bayese_640x640_nv12.yaml
模型转换完成后可以对模型进行可视化处理或者检查输入输出情况,具体命令如下:
hb_perf Car_Detect.bin #可视化模型
hrt_model_exec model_info --model_file Car_Detect.bin #检查bin模型的输入输出情况
接着我们使用Tros的dnn_node_example即可实现对车俩的检测
# 配置tros.b环境
source /opt/tros/humble/setup.bash
# 配置MIPI摄像头
export CAM_TYPE=usb
# 启动launch文件
ros2 launch dnn_node_example dnn_node_example.launch.py dnn_example_config_file:=(改为自己的模型config文件路径).json dnn_example_image_width:=480 dnn_example_image_height:=640
接着我们在同一个网络环境下输入http://IP:8000 IP:RDK X5的IP即可查看到实时的目标检测结果
3.2.2 部署ByteTrack多目标跟踪算法
单单是目标检测可还不行,我们还需要给每一个车一个独立的ID让计算机能智能分析知道哪台车下一刻在哪里以及这台车对应行为,于是我们需要引入多目标跟踪算法,多目标跟踪算法可以将目标在不同帧中的跟踪结果进行关联,以保持目标的身份一致性。目标关联算法需要根据目标的外观、运动和时空信息,将不同帧中的目标进行匹配和关联。常见的目标关联算法有基于外观特征的匹配方法(如卡尔曼滤波器、匈牙利算法等)和基于运动模型的匹配方法(如最近邻匹配、多目标数据关联等)等,我们这里使用ByteTrack算法。
ByteTrack算法是一种基于目标检测的追踪算法,和其他非ReID的算法一样,仅仅使用目标追踪所得到的bbox进行追踪。追踪算法使用了卡尔曼滤波预测边界框,然后使用匈牙利算法进行目标和轨迹间的匹配。其最大创新点就是对低分框的使用,作者认为低分框可能是对物体遮挡时产生的框,直接对低分框抛弃会影响性能,所以使用低分框对追踪算法进行了二次匹配,有效优化了追踪过程中因为遮挡造成换ID的问题。
我们按照Tros的规范输入输出在Yolo的输出和Web的显示之间再加一层Tracker包,这样就能得到每个识别结果唯一的ID
class oTracker : public rclcpp::Node {
public:
Tracker();
Tracker(const std::string &node_name) : Node(node_name) {
RCLCPP_INFO(this->get_logger(), "Tracker node is created");
this->declare_parameter("input_topic", "dnn_node_sample");
this->get_parameter("input_topic", input_topic_);
this->declare_parameter("output_topic", "tracker_res");
this->get_parameter("output_topic", output_topic_);
perception_subscription_ = this->create_subscription<ai_msgs::msg::PerceptionTargets>(
input_topic_, 10, std::bind(&YoloTracker::PerceptionCallback, this, std::placeholders::_1));
tracking_result_publisher_ = this->create_publisher<ai_msgs::msg::PerceptionTargets>(output_topic_, 10);
tracker_ = std::make_shared<BYTETracker>(30, 30);
}
private:
std::string input_topic_;
std::string output_topic_;
std::shared_ptr<BYTETracker> tracker_;
rclcpp::Subscription<ai_msgs::msg::PerceptionTargets>::SharedPtr perception_subscription_;
rclcpp::Publisher<ai_msgs::msg::PerceptionTargets>::SharedPtr tracking_result_publisher_;
void PerceptionCallback(const ai_msgs::msg::PerceptionTargets::SharedPtr msg) {
ai_msgs::msg::PerceptionTargets tracking_result;
std::vector<STrack> tracked_objects;
tracker_->update(msg, tracked_objects);
for (auto &tracked_object : tracked_objects) {
float xmin, ymin, xmax, ymax;
bool is_vertical = tracked_object.tlwh[2] / tracked_object.tlwh[3] > 1.6;
if (tracked_object.tlwh[2] * tracked_object.tlwh[3] > 20 && !is_vertical) {
xmin = tracked_object.tlwh[0];
ymin = tracked_object.tlwh[1];
xmax = tracked_object.tlwh[0] + tracked_object.tlwh[2];
ymax = tracked_object.tlwh[1] + tracked_object.tlwh[3];
}
ai_msgs::msg::Target target;
target.set__type(tracked_object.class_name);
ai_msgs::msg::Roi roi;
roi.rect.set__x_offset(xmin);
roi.rect.set__y_offset(ymin);
roi.rect.set__width(xmax - xmin);
roi.rect.set__height(ymax - ymin);
roi.set__confidence(tracked_object.score);
target.rois.emplace_back(roi);
target.set__track_id(tracked_object.track_id);
tracking_result.targets.emplace_back(std::move(target));
}
tracking_result.header = msg->header;
tracking_result.fps = msg->fps;
tracking_result_publisher_->publish(tracking_result);
}
};
接着我们再次在同一个网络环境下输入http://IP:8000 IP:RDK X5的IP,即可查看到实时的多目标跟踪结果,我们这里使用的是UA-DETRAC多图拼接生成的简短视频,可以看到追踪的效果还是很不错的
3.2.3 实现超速预警
实现了对目标车辆的追踪之后,我们便要写一个违章行为判定的算法,由于时间紧张(大三了11月是期末考试周ku.......)我用最简单的方式实现了超速的判定,具体流程为:首先通过OpenCV自动识别双向车道的中心线,接着自动生成两条垂直于车道线以及中心线的触发器,我们对检测进行多目标追踪后通过单个ID触发两条线的先后顺序、帧ID以及国内龙门架的平均高度4m即可综合判定出每个车辆的速度。
3.2.4 将违章报警信息发送至手机
得到了违法信息还不够,我们还需要将违法信息实时推送至管理人的手机,这里我们采用PushPlus(推送加作为我们推送服务的端口),使用PushPlus的方法很简单,注册一个账号后用微信公众号绑定即可获得一个API,通过这个API我们即可发送消息至公众号
使用的代码如下:
import requests
def send_wechat(msg):
token = ' '#粘贴自己的token
title = ' '
content = msg
template = 'html'
url = f"https://www.pushplus.plus/send?token={token}&title={title}&content={content}&template={template}"
print(url)
r = requests.get(url=url)
print(r.text)
if __name__ == '__main__':
msg = 'this is a python test'
send_wechat(msg)
如图所示:即可获得违章信息
3.2.5 交通堵塞热力图
(TODO)
3.2.6 数据库搭建
(TODO)
3.2.7 更多违章行为预警
(TODO)
四、孵化营总结
这次为其一个半月的孵化营的经历是宝贵的,每一次的闭门讨论会都让我收货满满,我也在群里结实了很多的大佬,但是但是时间真的好短呀!真的很抱歉没能完美的完成这个项目,对于大学生来说特别是期末周的大三生来说时间真的有些紧张,但是等我考完试我一定会把这个坑填上!希望下一次的孵化营可以把时间选在寒假(暑假有很多很多比赛任务)?