视觉巡线机器人-1.png

摘要
一个能够巡线运动的机器人的软件、硬件设计。

总体架构

视觉巡线机器人-2.png
系统有控制器、执行器、传感器三个部分构成。控制器包括:机载电脑(Nvidia Jetson Xavier NX)和STM32F103ZET6;执行器包括TB6612电机驱动和直流电机;传感器包括编码器和摄像头。

图像滤波

视觉巡线机器人-3.jpg
视觉巡线机器人-4.jpg
形态学滤波后图像如上图所示。

计算质心

先计算图像几何矩:
视觉巡线机器人-5.png
再计算图像质心:
视觉巡线机器人-6.png
将质心与图像分辨率的二分之一相减即可得到机器人行进方向与巡线方向的误差。

下位机接线图

视觉巡线机器人-7.png
这是一种接线方法,具体接线因硬件不同有区别。本项目中因为Jetson Xavier NX功耗较大因此单独配置电源适配器供电。实验中一定要注意将两个电源共地。


复现教程

0.环境配置
OpenCV:OpenCV配置教程
串口:串口配置教程
摄像头驱动(Astra S):摄像头驱动安装教程
建立工作区:

mkdir -p cv_ws/src 
cd src 
catkin_init_workspace 
cd .. 
catkin_make
cd src 
catkin_create_pkg (自定义包) roscpp std_msgs cv_bridge image_transport sensor_msgs serial_node serial 
cd .. 
catkin_make
cd src/(自定义包)/src
touch xxx.cpp xxx.cpp xxx.cpp

修改CMakeList.txt:

cd ~/cv_ws/src/包
vi CMakeList.txt

add_executable(功能1 xxx1.cpp)
add_executable(功能2 xxx2.cpp)
add_executable(功能3 xxx3.cpp)

target_link_libraries(功能1 ${catkin_LIBRARIES}  ${OpenCV_LIBS})
target_link_libraries(功能2 ${catkin_LIBRARIES}  ${OpenCV_LIBS})
target_link_libraries(功能3 ${catkin_LIBRARIES}  ${OpenCV_LIBS})

source

sudo echo “source ~/工作区/devel/setup.bash” >> ~/.bashsrc

1.上位机图像处理

  1. 基于OpenCV4的LineDetect类

    class LineDetect{
    public:
    cv::Mat img; //储存了原始图像
    cv::Mat img_filt; //储存了原始图像经滤波后的图像
    double dir; //储存小车目前行进方向与期望方向的误差
    cv::Scalar min; //储存RGB颜色范围的最小值
    cv::Scalar max; //储存RGB颜色范围的最大值
    cv::Mat img_hsv; //储存HSV格式的图像
    cv::Mat img_mask; //储存颜色识别的掩膜层(也可理解为二值化后的图像)
    cv::Mat img_mask_cut; //储存切割后的颜色识别掩膜层(以下简称黑白图像)
    cv::Mat mor1; //储存开运算后的黑白图像
    cv::Mat mor2; //储存闭运算后的黑白图像
    cv::Mat final_img; //储存标记了质心的原始图像
    //functions
    cv::Mat Gauss(cv::Mat input); //高斯滤波
    void binaryzation(cv::Mat input); //二值化
    cv::Mat img_cut(cv::Mat input); //切割图像
    cv::Mat morphology(cv::Mat input,int x,int k); //形态学滤波
    void distance(cv::Mat input); //计算质心及行进误差
    void imageCallback(const sensor_msgs::ImageConstPtr& msg); //在ROS中发布消息
    };

  2. 高斯滤波

    cv::Mat LineDetect::Gauss(cv::Mat input)
    {
    cv::Mat output;
    LineDetect::final_img = input;
    cv::GaussianBlur(input,output,cv::Size(3,3),0.1,0.1);
    return output;
    }

  3. 二值化

    void LineDetect::binaryzation(cv::Mat input)
    {
    cv::cvtColor(input,LineDetect::img_hsv,CV_BGR2HSV);

    //following values need to be changed when the environment changes
    LineDetect::min = {0,43,46};
    LineDetect::max = {10,255,255};
    
    cv::inRange(LineDetect::img_hsv,min,max,LineDetect::img_mask);

    }

  4. 图像切割

    cv::Mat LineDetect::img_cut(cv::Mat input)
    {
    cv::Size s = input.size();

        auto w = s.width;
        auto h = s.height;
    
        input(cv::Rect(0, 0.8*h, w, 0.2*h)) = 0;//Rect(w_start,h_start,w_length,h_length)
        input(cv::Rect(0, 0, w, 0.2*h)) = 0;    
    
        LineDetect::img_mask_cut = input;
        return input;

    }

  5. 形态学滤波

    cv::Mat LineDetect::morphology(cv::Mat input,int x,int k)
    {
    cv::Mat kernel = getStructuringElement(0,Size(k,k));
    if(x == 0)
    {
    cv::morphologyEx(input,LineDetect::mor1,MORPH_OPEN,kernel);
    return LineDetect::mor1;
    }
    else if(x == 1)
    {
    cv::morphologyEx(input,LineDetect::mor2,MORPH_CLOSE,kernel);
    return LineDetect::mor2;
    }
    }

  6. 计算质心和行进误差

    void LineDetect::distance(cv::Mat input)
    {
    cv::Moments M = cv::moments(input);
    cv::Point p1(M.m10/M.m00, M.m01/M.m00);//求质心
    //画圆
    cv::circle(LineDetect::mor2, p1, 5, cv::Scalar(0, 255, 0), -1);
    cv::circle(LineDetect::final_img,p1,10,cv::Scalar(0,255,0),-1);
    double c_x = M.m10/M.m00;
    LineDetect::dir = c_x - input.size().width/2;
    }

  7. 回调函数

    void LineDetect::imageCallback(const sensor_msgs::ImageConstPtr& msg)
    {
    cv_bridge::CvImagePtr cv_ptr;
    try {
    cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
    img = cv_ptr->image;
    cv::waitKey(30);
    }
    catch (cv_bridge::Exception& e) {
    ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
    }
    }

  8. 串口

    try
    {
    ser.setPort(“/dev/ttyTHS0”); //选择串口号(可以在cutecom等串口调试助手中查到)
    ser.setBaudrate(115200); //设置波特率
    serial::Timeout to = serial::Timeout::simpleTimeout(1000); //设置超时时间
    ser.setTimeout(to);
    ser.open(); //打开串口
    }
    catch (serial::IOException& e)
    {
    ROS_ERROR_STREAM("Unable to open port ");
    return -1;
    }
    if(ser.isOpen()){
    ROS_INFO_STREAM("Serial Port open");
    }else{
    return -1;
    }
    ros::Subscriber sub = nh.subscribe("error_distance",10,doMsg);

    void doMsg(const std_msgs::Float64 msg)
    {
    ROS_INFO("UART SEND DATA:%lf",msg.data);
    std::stringstream ss;
    std::string str;
    ss << std::setprecision(6) << msg.data; //把浮点数赋值给字符串,设置位数为6
    str = ss.str();
    ser.write(str); //把要发送的消息写到串口上

    }

2.下位机电机控制
下位机代码.zip

标签: 嵌入式控制

已有 6 条评论

  1. 科技狂人 科技狂人

    育才校友,国之栋梁!

  2. 叼茂SEO.bfbikes.com

  3. 不错不错,我喜欢看 www.jiwenlaw.com

  4. 你的文章让我感受到了无尽的欢乐,谢谢分享。 http://www.55baobei.com/YgnhNWAJtv.html

  5. 每次看到你的文章,我都觉得时间过得好快。 https://www.4006400989.com/qyvideo/94760.html

  6. 你的文章让我感受到了快乐,每天都要来看一看。 http://www.55baobei.com/ICcORkWRcf.html

添加新评论