基于arduino的5路循迹小车(5)与OpenMV的串口通信
进行图像识别,开发板控制舵机抓取物料
接第一篇链接 https://blog.csdn.net/weixin_45984029/article/details/103437347

1.硬件选用

OpenMV

在这里插入图片描述

2.接线

开发板与OpenMV的TX,RX交叉相连,VCC,GND对应相连

3.代码

arduino代码

#include <LobotServoController.h>

LobotServoController myse;

String comdata = "";

String data[4];//三个物块记录

String adata = ""; //大小控制
String bdata = "";
String cdata = "";

String aa="ZJGXDS01a";//大圆1
String ba="ZJGXDS02a";//大三角2
String ca="ZJGXDS03a";//大方3
String da="ZJGXDS04a";//大六边4
String ea="ZJGXDS05a";//大N5
String fa="ZJGXDS06a";//大星6

String ab="ZJGXDS01";//小圆7
String bb="ZJGXDS02";//小三角8
String cb="ZJGXDS03";//小方9
String db="ZJGXDS04";//小六边10
String eb="ZJGXDS05";//小N11
String fb="ZJGXDS06";//小星12

/**
* @par Copyright (C): 2010-2019, Shenzhen Yahboom Tech
* @file         tracking.c
* @author       Danny
* @version      V1.0
* @date         2017.07.26
* @brief        巡线实验
* @details
* @par History  见如下说明
*
*/
unsigned long time1;            //计时 

int Left_motor_go1 = 24;        //左电机前进 AIN1
int Left_motor_back1 = 25;      //左电机后退 AIN2

int Right_motor_go1 = 22;       //右电机前进 BIN1
int Right_motor_back1 = 23;     //右电机后退 BIN2

int Left_motor_pwm1 = 3;       //左电机控速 PWMA
int Right_motor_pwm1= 5;      //右电机控速 PWMB
int Left_motor_pwm2 = 4;       //左电机控速 PWMA
int Right_motor_pwm2= 6;    

int echoPin   = 32; //超声波
int trigPin   = 33;
unsigned int S;

int i;
int a;

int b;//物块记录

int e;
int f;
int s;

int G1 = 26;
int G2 = 27;
int G3 = 28;
int G4 = 29;
int G5 = 30;

//循迹红外引脚定义
//TrackSensorLeftPin1 TrackSensorLeftPin2 TrackSensorMid TrackSensorRightPin1 TrackSensorRightPin2 
//      A1                   A2                  A3                   A4                A5
const int TrackSensorLeftPin1  =  A1;  //定义第一个循迹红外传感器引脚为A1
const int TrackSensorLeftPin2  =  A2;  //定义第二个循迹红外传感器引脚为A2
const int TrackSensorMid = A3;       //定义第三个循迹红外传感器引脚为A3
const int TrackSensorRightPin1 =  A4;  //定义第四个循迹红外传感器引脚为A4
const int TrackSensorRightPin2 =  A5;  //定义第五个循迹红外传感器引脚为A5

// TrackSensorRightPin3 进行计数
//        A6              
const int TrackSensorRightPin3 =  A6;  //右主计数 

//定义各个循迹红外引脚采集的数据的变量
int SLL;
int SL;
int SM;
int SR;
int SRR;

//定义计数变量
int JS2;

/**
* Function       setup
* @author        Danny
* @date          2017.07.25
* @brief         初始化配置
* @param[in]     void
* @retval        void
* @par History   无
*/
void setup()
{
  Serial.begin(9600);//超声波
  Serial1.begin(9600);
  Serial3.begin(9600);
  pinMode(13,OUTPUT);
  
  digitalWrite(13,LOW);
  while(!Serial1);
  digitalWrite(13,HIGH);

  
  pinMode(trigPin, OUTPUT);
  pinMode(echoPin, INPUT);
  //初始化电机驱动IO口为输出方式
  pinMode(Left_motor_go1, OUTPUT);
  pinMode(Left_motor_back1, OUTPUT);
  pinMode(Right_motor_go1, OUTPUT);
  pinMode(Right_motor_back1, OUTPUT);

  //初始化语音输出
  pinMode(G1, OUTPUT);
  pinMode(G2, OUTPUT);
  pinMode(G3, OUTPUT);
  pinMode(G4, OUTPUT);
  pinMode(G5, OUTPUT);

  digitalWrite(G1, HIGH);
  digitalWrite(G2, HIGH);
  digitalWrite(G3, HIGH);
  digitalWrite(G4, HIGH);
  digitalWrite(G5, HIGH);

  //定义四路循迹红外传感器为输入接口
  pinMode(TrackSensorLeftPin1, INPUT);
  pinMode(TrackSensorLeftPin2, INPUT);
  pinMode(TrackSensorMid,INPUT);
  pinMode(TrackSensorRightPin1, INPUT);
  pinMode(TrackSensorRightPin2, INPUT);

  //定义计数传感器输入接口
  pinMode(TrackSensorRightPin3, INPUT);
  
  //四路循迹红外传感器初始化为高电平
  digitalWrite(TrackSensorLeftPin1, HIGH);
  digitalWrite(TrackSensorLeftPin2, HIGH);
  digitalWrite(TrackSensorMid,HIGH);
  digitalWrite(TrackSensorRightPin1, HIGH);
  digitalWrite(TrackSensorRightPin2, HIGH);
  
  digitalWrite(TrackSensorRightPin3, HIGH);

  digitalWrite(G1, LOW);
  delay(1500);//预热
  run(50,43);//起步
  delay(1000);
  myse.runActionGroup(102,1);//初始化舵机

  i = 0;
  e = 1;
  f = 1;
}

/**
* Function       run
* @author        Danny
* @date          2017.07.26
* @brief         小车前进
* @param[in1]    left_speed:左轮速度
* @param[in2]    right_speed:右轮速度
* @param[out]    void
* @retval        void
* @par History   无
*/
void run(int left_speed, int right_speed)
{
  //左电机前进
  digitalWrite(Left_motor_go1, LOW);   //左电机前进使能
  digitalWrite(Left_motor_back1, HIGH);  //左电机后退禁止
  analogWrite(Left_motor_pwm1, LOW);
  analogWrite(Left_motor_pwm2, left_speed);
  //右电机前进
  digitalWrite(Right_motor_go1, LOW);  //右电机前进使能
  digitalWrite(Right_motor_back1, HIGH); //右电机后退禁止
  analogWrite(Right_motor_pwm1, LOW);
  analogWrite(Right_motor_pwm2, right_speed);
}

/**
* Function       brake
* @author        Danny
* @date          2017.07.25
* @brief         小车刹车
* @param[in]     time:延时时间
* @param[out]    void
* @retval        void
* @par History   无
*/


void  left(int left_speed, int right_speed)
{
  //左电机停止
  digitalWrite(Left_motor_go1, HIGH);    //左电机前进禁止
  digitalWrite(Left_motor_back1,LOW);  //左电机后退禁止
  analogWrite(Left_motor_pwm2, left_speed);
  analogWrite(Left_motor_pwm1,LOW);

  //右电机前进
  digitalWrite(Right_motor_go1, LOW);  //右电机前进使能
  digitalWrite(Right_motor_back1, HIGH); //右电机后退禁止
  analogWrite(Right_motor_pwm2, LOW);
  analogWrite(Right_motor_pwm1, right_speed);
}


void right(int left_speed, int right_speed)
{
  //左电机前进
  digitalWrite(Left_motor_go1, LOW);   //左电机前进使能
  digitalWrite(Left_motor_back1, HIGH);  //左电机后退禁止
  analogWrite(Left_motor_pwm2, LOW);
  analogWrite(Left_motor_pwm1, left_speed);

  //右电机停止
  digitalWrite(Right_motor_go1, HIGH );   //右电机前进禁止
  digitalWrite(Right_motor_back1,LOW); //右电机后退禁止
  analogWrite(Right_motor_pwm2, right_speed);
  analogWrite(Right_motor_pwm1, LOW );

}

void back(int left_speed, int right_speed)
{
  //左电机前进
  digitalWrite(Left_motor_go1, HIGH);   //左电机前进使能
  digitalWrite(Left_motor_back1, LOW);  //左电机后退禁止
  analogWrite(Left_motor_pwm1, left_speed);
  analogWrite(Left_motor_pwm2, LOW);
  //右电机前进
  digitalWrite(Right_motor_go1, HIGH);  //右电机前进使能
  digitalWrite(Right_motor_back1, LOW); //右电机后退禁止
  analogWrite(Right_motor_pwm1, right_speed);
  analogWrite(Right_motor_pwm2, LOW);
}

void barke(int left_speed, int right_speed)
{
  //左电机停止
  digitalWrite(Left_motor_go1, HIGH);   //左电机前进使能
  digitalWrite(Left_motor_back1, HIGH);  //左电机后退禁止
  analogWrite(Left_motor_pwm1, left_speed);
  analogWrite(Left_motor_pwm2, left_speed);

  //右电机停止
  digitalWrite(Right_motor_go1, HIGH );   //右电机前进禁止
  digitalWrite(Right_motor_back1,HIGH); //右电机后退禁止
  analogWrite(Right_motor_pwm1, right_speed);
  analogWrite(Right_motor_pwm2, right_speed);
  
}
void bank(int left_speed, int right_speed)
{
  //左电机空
  digitalWrite(Left_motor_go1, LOW);   //左电机前进使能
  digitalWrite(Left_motor_back1, LOW);  //左电机后退禁止
  analogWrite(Left_motor_pwm1, left_speed);
  analogWrite(Left_motor_pwm2, left_speed);

  //右电机空
  digitalWrite(Right_motor_go1, LOW);   //右电机前进禁止
  digitalWrite(Right_motor_back1,LOW); //右电机后退禁止
  analogWrite(Right_motor_pwm1, right_speed);
  analogWrite(Right_motor_pwm2, right_speed);
  
}
void BZ()//避障程序
{
  digitalWrite(G4, LOW);
  delay(100);
  barke(120,120);
  delay(600);
  bank(0,0);
  delay(300);
  
  back(45,37);
  delay(300);
  barke(120,120);
  delay(300);
  bank(0,0);
  delay(300);
  
  left(55,65);
  delay(700);
  run(55,55);
  delay(1000);
  right(55,45);
  delay(400);
  run(55,55);
  delay(1000);
  right(55,45);
  delay(400);
  run(55,55);
  delay(1046);
  left(55,55);
  delay(550);
  
}
void range()

 digitalWrite(trigPin,LOW); //测距
 delayMicroseconds(2); //延时2微秒
 digitalWrite(trigPin,HIGH);
 delayMicroseconds(20);
 digitalWrite(trigPin,LOW);
 int distance = pulseIn(echoPin,HIGH); //读取高电平时间
 distance = distance/58; 
 S = distance; //把值赋给S
 if( S < 16 )
      { 
      BZ();
      }
}


void loop()
{
  xunji();//调用循迹
 if(JS2 == HIGH)
   {
    a++;
    i++;

    if(a == 1)
    {
    barke(120,120);//停车
    delay(650);
    bank(0,0);
    delay(1000);
   
     if(i == 1)
    {
      
      digitalWrite(G3, LOW);
      myse.runActionGroup(100,1);  //运行100号识别1组
      delay(2000);
      /*scan();//识别
      shangp();*/
      myse.runActionGroup(26,1);
      delay(16000);
    }
    if(i == 2)
    {
      myse.runActionGroup(100,1);  //运行100号识别1组
      delay(2000);
      /*scan();//识别
      shangp();*/
      myse.runActionGroup(27,1);
      delay(16000);
    }
    if(i == 3)
    {
      myse.runActionGroup(100,1);  //运行100号识别1组
      delay(2000);
      /*scan();//识别
      shangp();*/
      myse.runActionGroup(28,1);
      delay(16000);
      myse.runActionGroup(110,1);  //运行110号动作组
      delay(4000);
      bank(0,0);
      delay(1000);
      run(42,34);
      delay(300);
      run(15,8);
      delay(500);
    }
    if(i == 4)
    {
      myse.runActionGroup(98,1);  //运行98号动作组
      delay(2000);
      run(50,42);
      delay(400);
     return;
    }
    
    if(i == 5)//下料
    {
      
      /*scan();//识别
      fangp();*/
    }
    if(i == 6)
    {
      
      /*scan();//识别
      fangp();*/
    }
    if(i == 7)
    {
      
      /*scan();//识别
      fangp();*/
    }
    if(i == 8)
    {
      digitalWrite(G5, LOW);
      myse.runActionGroup(81,1);  //运行101号识别2组
      delay(16000);
      /*myse.runActionGroup(101,1);  //运行101号识别2组
      delay(4000);
      scan();//识别
      fangp();*/
    }
    if(i == 9)
    {
      myse.runActionGroup(82,1);  //运行101号识别2组
      delay(16000);
      /*myse.runActionGroup(101,1);  //运行101号识别2组
      delay(4000);
      scan();//识别
      fangp();*/
    }
    if(i == 10)
    {
      myse.runActionGroup(83,1);  //运行101号识别2组
      delay(16000);
      /*myse.runActionGroup(101,1);  //运行101号识别2组
      delay(4000);
      scan();//识别
      fangp();*/
    }
      run(100,90);
      delay(200);
      return;
      
    }
   }
   range();
}

void xunji()//循迹
{
  a = 0;
  time1 = millis();
  if(time1 == 8000)
  {
    digitalWrite(G2, LOW);
  }
  //检测到黑线时循迹模块相应的指示灯灭,端口电平为HIGH
  //未检测到黑线时循迹模块相应的指示灯亮,端口电平为LOW
  
  SLL  = digitalRead(TrackSensorLeftPin1);
  SL  = digitalRead(TrackSensorLeftPin2);
  SM = digitalRead(TrackSensorMid);
  SR = digitalRead(TrackSensorRightPin1);
  SRR = digitalRead(TrackSensorRightPin2);

  //计数

  JS2 = digitalRead(TrackSensorRightPin3);

 //循迹
  if( SM == HIGH )
  {
      run(45,37);                                                                                                                  
  }
  if( SL == HIGH && SM == LOW)
  {
    
    left(35,57);
  }
  if( SLL == HIGH && SM == LOW)
  {
    
    left(35,57);
  }
  if( SR == HIGH && SM == LOW)
  {
    
    right(50,32);
  }
  if( SRR == HIGH && SM == LOW)
  {
    right(50,32);
  }
  if(SR == HIGH && SRR == HIGH)
 {
  right(50,32);
 }
 if(SL == HIGH && SLL == HIGH)
 {
  left(30,57);
 }
  if(SRR == HIGH && SR == HIGH && SM == HIGH && SL == HIGH)
 {
  right(50,32);
 }

  if(SM == HIGH && (SL == HIGH && SLL == HIGH) || (SR == HIGH && SL == HIGH) || (SR == HIGH && SRR == HIGH))
 {
  run(45,37);
 }

}

void scan()
{
   comdata = "";  
   while(Serial3.available()>0)//读取串口
   {
      char inChar=Serial3.read();
      comdata+=(char)inChar;
      delay(10);
    }
   if(comdata!=NULL)
   {
     if(comdata == aa)//大
     {
        b = 1;
     }
     if(comdata == ba)
     {
        b = 2;
     }
     if(comdata == ca)
     {
        b = 3;
     }
     if(comdata == da)
     {
        b = 4;
     }
     if(comdata == ea)
     {
        b = 5;
     }
     if(comdata == fa)
     {
        b = 6;
     }
     if(comdata == ab)//小
     {
        b = 7;
     }
     if(comdata == bb)
     {
        b = 8;
     }
     if(comdata == cb)
     {
        b = 9;
     }
     if(comdata == db)
     {
        b = 10;
     }
     if(comdata == eb)
     {
        b = 11;
     }
     if(comdata == fb)
     {
        b = 12;
     }
  }
}
void shangp()//上料
{
  if(e <= 3)
  {
   data[f] = comdata;
   f++;
  }
  if(e > 3)//次数
  {
  exit;
  }
  if(b == 1)//3个为一组
  {
   if(e == 1)
   {
  myse.runActionGroup(1,1);  //运行98号动作组
  delay(2000);
   }
   if(e == 2)
   {
  myse.runActionGroup(2,1);  //运行98号动作组
  delay(2000);
   }
   if(e == 3)
   {
  myse.runActionGroup(3,1);  //运行98号动作组
  delay(2000);
   }
  }

  if(b == 2)
  {
   if(e == 1)
   {
  myse.runActionGroup(4,1);  //运行4号动作组
  delay(2000);
   }
   if(e == 2)
   {
  myse.runActionGroup(5,1);  //运行98号动作组
  delay(2000);
   }
   if(e == 3)
   {
  myse.runActionGroup(6,1);  //运行98号动作组
  delay(2000);
   }
  }
  if(b == 3)
  {
   if(e == 1)
   {
  myse.runActionGroup(7,1);  //运行98号动作组
  delay(15000);
   }
   if(e == 2)
   {
  myse.runActionGroup(8,1);  //运行98号动作组
  delay(15000);
   }
   if(e == 3)
   {
  myse.runActionGroup(9,1);  //运行98号动作组
  delay(15000);
   }
  }
  if(b == 4)
  {
   if(e == 1)
   {
  myse.runActionGroup(10,1);  //运行98号动作组
  delay(15000);
   }
   if(e == 2)
   {
  myse.runActionGroup(11,1);  //运行98号动作组
  delay(15000);
   }
   if(e == 3)
   {
  myse.runActionGroup(12,1);  //运行98号动作组
  delay(15000);
   }
  }
  if(b == 5)
  {
   if(e == 1)
   {
  myse.runActionGroup(13,1);  //运行98号动作组
  delay(15000);
   }
   if(e == 2)
   {
  myse.runActionGroup(14,1);  //运行98号动作组
  delay(15000);
   }
   if(e == 3)
   {
  myse.runActionGroup(15,1);  //运行98号动作组
  delay(15000);
   }
  }
  if(b == 6)
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(2000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(2000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   }
  }
  if(b == 7)//小
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   }
  }
  if(b == 8)
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   }
  }
  if(b == 9)
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   }
  }
  if(b == 10)
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   }
  }
  if(b == 11)
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   }
  }
  if(b == 12)
  {
   if(e == 1)
   {
  myse.runActionGroup(26,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 2)
   {
  myse.runActionGroup(27,1);  //运行98号动作组
  delay(16000);
   }
   if(e == 3)
   {
  myse.runActionGroup(28,1);  //运行98号动作组
  delay(16000);
   } 
  }
  e++;
}

OpenMV代码

# Template Matching Example - Normalized Cross Correlation (NCC)
#
# This example shows off how to use the NCC feature of your OpenMV Cam to match
# image patches to parts of an image... expect for extremely controlled enviorments
# NCC is not all to useful.
#
# WARNING: NCC supports needs to be reworked! As of right now this feature needs
# a lot of work to be made into somethin useful. This script will reamin to show
# that the functionality exists, but, in its current state is inadequate.

from pyb import UART

import time, sensor, image
from image import SEARCH_EX, SEARCH_DS

# Reset sensor
sensor.reset()

# Set sensor settings
sensor.set_contrast(1)
sensor.set_gainceiling(16)
# Max resolution for template matching with SEARCH_EX is QQVGA
sensor.set_framesize(sensor.QQVGA)
# You can set windowing to reduce the search image.
#sensor.set_windowing(((640-80)//2, (480-60)//2, 80, 60))
sensor.set_pixformat(sensor.GRAYSCALE)


sensor.skip_frames(10)
sensor.set_auto_whitebal(False)

# Load template.
# Template should be a small (eg. 32x32 pixels) grayscale image.
fangxing1 = image.Image("/FX1.pgm")
fangxing2 = image.Image("/FX2.pgm")
fangxing3 = image.Image("/FX3.pgm")
saojiao1 = image.Image("/SJ1.pgm")
liubian1 = image.Image("/LB1.pgm")
Nzi1 = image.Image("/NZ1.pgm")
Nzi2 = image.Image("/NZ2.pgm")
Nzi3 = image.Image("/NZ3.pgm")
clock = time.clock()

uart = UART(3, 9600)

# Run template matching
while (True):
    clock.tick()
    img = sensor.snapshot()

    # find_template(template, threshold, [roi, step, search])
    # ROI: The region of interest tuple (x, y, w, h).
    # Step: The loop step used (y+=step, x+=step) use a bigger step to make it faster.
    # Search is either image.SEARCH_EX for exhaustive search or image.SEARCH_DS for diamond search
    #
    # Note1: ROI has to be smaller than the image and bigger than the template.
    # Note2: In diamond search, step and ROI are both ignored.
    r1 = img.find_template(saojiao1, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r1:
        img.draw_rectangle(r1)
        uart.write("ZJGXDS02")
        time.sleep(1000)


    r5 = img.find_template(fangxing1, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r5:
        img.draw_rectangle(r5)
        uart.write("ZJGXDS03")
        time.sleep(1000)
    r51 = img.find_template(fangxing2, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r51:
        img.draw_rectangle(r51)
        uart.write("ZJGXDS03")
        time.sleep(1000)
    r52 = img.find_template(fangxing3, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r52:
        img.draw_rectangle(r52)
        uart.write("ZJGXDS03")
        time.sleep(1000)
    r7 = img.find_template(liubian1, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r7:
        img.draw_rectangle(r7)
        uart.write("ZJGXDS04")
        time.sleep(1000)
    r9 = img.find_template(Nzi1, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r9:
        img.draw_rectangle(r9)
        uart.write("ZJGXDS05")
        time.sleep(1000)
    r91 = img.find_template(Nzi2, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r91:
        img.draw_rectangle(r91)
        uart.write("ZJGXDS05")
        time.sleep(1000)
    r92 = img.find_template(Nzi3, 0.70, step=4, search=SEARCH_EX) #, roi=(10, 0, 60, 60))
    if r92:
        img.draw_rectangle(r92)
        uart.write("ZJGXDS05")
        time.sleep(1000)


    print(clock.fps())

4.测试小车

OpenMV的NCC算法模板匹配使用灰度图
因内存有限,模板匹配的模板不能太大
模板图片格式为PGM