AI模型部署边缘设备的奇妙之旅:视觉巡线 原创

福州市凌睿智捷电子有限公司
发布于 2025-3-31 11:04
1309浏览
0收藏

1、项目简介

在本次项目中,我们将采用LockAI视觉摄像头与OpenCV-C++技术相结合的方式来实现特定场地内的视觉巡线任务。

控制方面,我们选用了小凌派-RK2206开发板,该开发板运行OpenHarmony请谅解操作系统,并通过串口通讯与LockAI进行高效的数据交互。基于摄像头传输回来的目标坐标数据,我们将运用PID算法精确地对智能车的行驶进行调控。这样,不仅能够确保智能车沿着预定线路稳定行驶,还能通过实时数据分析优化行车路径,提升整体运行效率和稳定性。整个方案集成了先进的图像识别技术和精准的控制算法,为实现自动化巡线提供了可靠的技术保障。

2、基本知识

2.1、PID算法简介

PID算法,即比例-积分-微分(Proportional-Integral-Derivative)控制器,是一种在工业控制中广泛应用的反馈控制机制。它通过计算设定值(目标值)与实际值之间的误差,并基于此误差进行调节,以达到稳定系统输出的目的。其原理如下:

  1. 比例(P)控制:比例控制是根据当前误差值(即设定值与实际值之差)直接按比例调整输出。它的作用是快速响应误差,减少误差幅度。比例系数Kp越大,调节的速度越快,但是过大的Kp会导致系统振荡。
  2. 积分(I)控制:积分控制是对过去所有误差的累积进行调节,其目的是消除静差(即系统稳定后仍然存在的误差)。积分项通过累加过去的误差来影响控制量,使得即使误差很小,只要持续存在,也会逐渐增加控制量,直到误差被完全消除。积分系数Ki需要谨慎选择,因为太高的积分作用可能导致系统不稳定。
  3. 微分(D)控制:微分控制考虑的是误差的变化率,用于预测误差的未来趋势,从而提前采取措施减小误差。微分项能够帮助抑制超调现象,提高系统的响应速度和平稳性。然而,由于它对噪声较为敏感,因此实际应用中往往需要慎重设置微分系数Kd。

在实际的控制过程中我们采用离散型PID控制。在离散时间系统中,假设采样周期为TT,则离散型PID控制器的输出u(k)u(k)可以表示为: u(k)=Kpe(k)+Ki∑i=0kTe(i)+Kde(k)−e(k−1)Tu(k)=Kpe(k)+K**ii=0kTe(i)+KdT**e(k)−e(k−1) 其中,

  • KpK**p、KiK**i 和 KdK**d 分别为比例、积分和微分系数。
  • e(k)e(k) 代表第kk次采样时的误差,即设定值与实际值之差。
  • TT 是采样时间间隔。

为了更有效地实现积分项的计算,通常采用增量式PID算法,其表达式为: Δu(k)=u(k)−u(k−1)=Kp[e(k)−e(k−1)]+KiTe(k)+Kde(k)−2e(k−1)+e(k−2)TΔu(k)=u(k)−u(k−1)=K**p[e(k)−e(k−1)]+KiT**e(k)+KdT**e(k)−2e(k−1)+e(k−2)

这样做的好处在于,只需保存最近几次的误差值以及上一次的控制量,就可以计算出当前的控制增量Δu(k)Δu(k),从而减少了存储需求,并且易于编程实现。

2.2、LockAI简介

凌智视觉模块(Lockzhiner Vision Module) 是福州市凌睿智捷电子有限公司联合百度飞桨倾力打造的一款高集成度人工智能视觉模块,专为边缘端人工智能和机器视觉应用而设计。读者如有兴趣,可以参考Gitee仓库(LockAI Gitee仓

3、实验内容

3.1、视觉代码实现

本项目是基于摄像头的视觉检测系统,主要功能包括实时捕获视频流、提取感兴趣区域(ROI)、通过 HSV 阈值分割检测黑色区域,并计算目标质心位置以确定水平偏移量。系统通过串口将质心 X 坐标发送给外部设备(如小车控制器),同时在图像上绘制 ROI 边框和质心位置,并将处理结果发送至编辑模块进行显示,便于调试和验证。代码采用模块化设计,支持动态调整摄像头分辨率,具备良好的灵活性和扩展性,适用于智能车视觉巡线、目标跟踪等场景。为进一步提升性能,建议增强异常处理机制、优化算法效率,并将关键参数提取到配置文件中以便于调整和适配不同环境。整体而言,该系统实现了实时性、可视化与模块化的结合,为嵌入式视觉应用提供了可靠的技术支持。

#include <lockzhiner_vision_module/edit/edit.h>
#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/opencv.hpp>
#include <lockzhiner_vision_module/periphery/usart/usart.h>

int main(int argc, char *argv[])
{
    // 设置串口波特率为115200
    lockzhiner_vision_module::periphery::USART1 usart;
    if (!usart.Open(115200))
    {
        std::cout << "Failed to open usart." << std::endl;
        return 1;
    }
    // 设置默认摄像头分辨率
    int width = 640;
    int height = 480;

    // 如果命令行参数提供了宽度和高度,则使用它们
    if (argc == 3)
    {
        width = std::stoi(argv[1]);
        height = std::stoi(argv[2]);
    }

    // 初始化编辑模块并尝试连接设备
    lockzhiner_vision_module::edit::Edit edit;
    if (!edit.StartAndAcceptConnection())
    {
        std::cerr << "Error: Failed to start and accept connection." << std::endl;
        return EXIT_FAILURE;
    }
    std::cout << "Device connected successfully." << std::endl;

    cv::VideoCapture cap;
    cap.set(cv::CAP_PROP_FRAME_WIDTH, width);
    cap.set(cv::CAP_PROP_FRAME_HEIGHT, height);
    cap.open(0);
    // 获取实际的帧尺寸
    double frameWidth = cap.get(cv::CAP_PROP_FRAME_WIDTH);
    double frameHeight = cap.get(cv::CAP_PROP_FRAME_HEIGHT);
    std::cout << "Frame size: " << frameWidth << "x" << frameHeight << std::endl;

    // 定义ROI区域
    cv::Rect roi_rect(100, 400, 440, 80);

    while (true)
    {
        cv::Mat temp_mat;
        cap >> temp_mat; // 获取新的一帧
        if (temp_mat.empty())
        {
            std::cerr << "Warning: Couldn't read a frame from the camera." << std::endl;
            continue;
        }

        // 提取ROI区域,并转换到HSV色彩空间
        cv::Mat roi_image = temp_mat(roi_rect);
        cv::cvtColor(roi_image, roi_image, cv::COLOR_BGR2HSV); // 注意原代码中是RGB2HSV,应改为BGR2HSV

        // 创建黑白掩膜
        cv::Scalar lower_black(0, 0, 0);
        cv::Scalar upper_black(180, 100, 60);
        cv::Mat mask;
        cv::inRange(roi_image, lower_black, upper_black, mask);

        // 应用掩膜
        cv::Mat res;
        cv::bitwise_and(roi_image, roi_image, res, mask);

        // 计算图像矩并找到质心
        cv::Moments m = cv::moments(mask, false);
        double cx = m.m10 / (m.m00 + 1e-6); // 防止除以零
        double cy = m.m01 / (m.m00 + 1e-6);

        // 在原始图像上绘制ROI边框和质心位置
        cv::rectangle(temp_mat, roi_rect, cv::Scalar(255, 0, 0), 2);                                                                         // 绘制ROI边框
        cv::circle(temp_mat, cv::Point(static_cast<int>(cx + roi_rect.x), static_cast<int>(cy + roi_rect.y)), 5, cv::Scalar(0, 255, 0), -1); // 绿色圆点表示质心位置

        // 输出质心的X坐标
        std::cout << "Centroid X: " << cx + roi_rect.x << std::endl;

        std::string prefix = "x:";
        std::ostringstream stream;
        stream << prefix << (cx + roi_rect.x) << "\r\n";
        std::string result = stream.str();
        if (!usart.Write(result))
        {
            std::cout << "Failed to send data." << std::endl;
        }
        // 将当前帧发送到编辑模块打印
        if (!edit.Print(temp_mat))
        {
            std::cerr << "Error: Failed to print to edit module." << std::endl;
            break;
        }
    }

    return EXIT_SUCCESS;
}
  • 1.
  • 2.
  • 3.
  • 4.
  • 5.
  • 6.
  • 7.
  • 8.
  • 9.
  • 10.
  • 11.
  • 12.
  • 13.
  • 14.
  • 15.
  • 16.
  • 17.
  • 18.
  • 19.
  • 20.
  • 21.
  • 22.
  • 23.
  • 24.
  • 25.
  • 26.
  • 27.
  • 28.
  • 29.
  • 30.
  • 31.
  • 32.
  • 33.
  • 34.
  • 35.
  • 36.
  • 37.
  • 38.
  • 39.
  • 40.
  • 41.
  • 42.
  • 43.
  • 44.
  • 45.
  • 46.
  • 47.
  • 48.
  • 49.
  • 50.
  • 51.
  • 52.
  • 53.
  • 54.
  • 55.
  • 56.
  • 57.
  • 58.
  • 59.
  • 60.
  • 61.
  • 62.
  • 63.
  • 64.
  • 65.
  • 66.
  • 67.
  • 68.
  • 69.
  • 70.
  • 71.
  • 72.
  • 73.
  • 74.
  • 75.
  • 76.
  • 77.
  • 78.
  • 79.
  • 80.
  • 81.
  • 82.
  • 83.
  • 84.
  • 85.
  • 86.
  • 87.
  • 88.
  • 89.
  • 90.
  • 91.
  • 92.
  • 93.
  • 94.
  • 95.
  • 96.
  • 97.
  • 98.
  • 99.
  • 100.
  • 101.
  • 102.
  • 103.

3.2、PID代码实现

本项目主要通过串口与 LockAI 摄像头进行通信,并在串口任务中解析出目标的关键数据,例如目标的质心坐标、目标检测区域的大小等信息。这些数据被用作 PID 控制器的反馈输入,进而计算出 PID 的输出值。小凌派开发板基于该输出值实现了麦克纳姆轮的运动解算。只需输入期望的 X 轴、Y 轴以及旋转 W 轴的速度,即可通过解算函数计算出四个轮子对应的速度。各轴的速度会自动叠加,确保运动的平滑性与精确性。将 PID 的输出结果输入到麦克纳姆轮的解算函数中,即可实现对小车车身姿态和运动的精准控制。

float PID_Calc(PidTypeDef *pid, float ref, float set)
{
    if (pid == NULL)
    {
        return 0.0f;
    }

    pid->error[2] = pid->error[1];
    pid->error[1] = pid->error[0];
    pid->set = set;
    pid->fdb = ref;
    pid->error[0] = set - ref;

    if (pid->mode == PID_POSITION)
    {
        pid->Pout = pid->Kp * pid->error[0];
        pid->Iout += pid->Ki * pid->error[0];
        pid->Dbuf[2] = pid->Dbuf[1];
        pid->Dbuf[1] = pid->Dbuf[0];
        pid->Dbuf[0] = (pid->error[0] - pid->error[1]);
        pid->Dout = pid->Kd * pid->Dbuf[0];
        LimitMax(pid->Iout, pid->max_iout);
        pid->out = pid->Pout + pid->Iout + pid->Dout;
        LimitMax(pid->out, pid->max_out);
    }
    else if (pid->mode == PID_DELTA)
    {
        pid->Pout = pid->Kp * (pid->error[0] - pid->error[1]);
        pid->Iout = pid->Ki * pid->error[0];
        pid->Dbuf[2] = pid->Dbuf[1];
        pid->Dbuf[1] = pid->Dbuf[0];
        pid->Dbuf[0] = (pid->error[0] - 2.0f * pid->error[1] + pid->error[2]);
        pid->Dout = pid->Kd * pid->Dbuf[0];
        pid->out += pid->Pout + pid->Iout + pid->Dout;
        LimitMax(pid->out, pid->max_out);
    }

    return pid->out;
}

void UserControl()
{
    WheelControl wheelControls[WHEELS_COUNT];
    float vx = 0; // X方向线速度,单位:m/s
    float vy = 0; // Y方向线速度,单位:m/s
    float w = 0;  // 角速度,单位:rad/s

    CtrolInit();

    for (;;)
    {
        // PID_Calc(&PWMPid[0], x, 320);
        // PID_Calc(&PWMPid[0], x, 320);
        if (FirstRec == 1)
        {
            // 检测用
            // PID_Calc(&PWMPid[2], x, 240);
            // PID_Calc(&PWMPid[1], s, 10000);
            // calculateWheelPWMSpeeds(-PWMPid[1].out, vy, PWMPid[2].out, wheelControls);
            // 循迹用
            PID_Calc(&PWMPid[2], x, 240);
            calculateWheelPWMSpeeds(-5, vy, PWMPid[2].out, wheelControls);

            // 设置方向GPIO
            LzGpioSetVal(GPIO0_PA5, wheelControls[0].direction); // 右前
            LzGpioSetVal(GPIO0_PA3, wheelControls[3].direction); // 右后
            LzGpioSetVal(GPIO0_PA1, wheelControls[2].direction); // 左后
            LzGpioSetVal(GPIO0_PA0, wheelControls[1].direction); // 左前

            // 启动PWM
            IoTPwmStart(RU_B4, wheelControls[0].pwm, 1000); // 右前
            IoTPwmStart(RD_B6, wheelControls[3].pwm, 1000); // 右后
            IoTPwmStart(LD_C7, wheelControls[2].pwm, 1000); // 左后
            IoTPwmStart(LU_C3, wheelControls[1].pwm, 1000); // 左前
        }

        LOS_Msleep(1);
    }
}
  • 1.
  • 2.
  • 3.
  • 4.
  • 5.
  • 6.
  • 7.
  • 8.
  • 9.
  • 10.
  • 11.
  • 12.
  • 13.
  • 14.
  • 15.
  • 16.
  • 17.
  • 18.
  • 19.
  • 20.
  • 21.
  • 22.
  • 23.
  • 24.
  • 25.
  • 26.
  • 27.
  • 28.
  • 29.
  • 30.
  • 31.
  • 32.
  • 33.
  • 34.
  • 35.
  • 36.
  • 37.
  • 38.
  • 39.
  • 40.
  • 41.
  • 42.
  • 43.
  • 44.
  • 45.
  • 46.
  • 47.
  • 48.
  • 49.
  • 50.
  • 51.
  • 52.
  • 53.
  • 54.
  • 55.
  • 56.
  • 57.
  • 58.
  • 59.
  • 60.
  • 61.
  • 62.
  • 63.
  • 64.
  • 65.
  • 66.
  • 67.
  • 68.
  • 69.
  • 70.
  • 71.
  • 72.
  • 73.
  • 74.
  • 75.
  • 76.
  • 77.
  • 78.
  • 79.

4、实验结果

AI模型部署边缘设备的奇妙之旅:视觉巡线

©著作权归作者所有,如需转载,请注明出处,否则将追究法律责任
分类
标签
收藏
回复
举报


回复
    相关推荐