Microduino Pixy摄像头SPI通讯追踪颜色/zh

来自Microduino Wikipedia
Wasdpkj@hotmail.com讨论 | 贡献2016年1月7日 (四) 05:12的版本 (Wasdpkj@hotmail.com moved page Microduino与Pixy摄像头SPI通讯追踪颜色/zh to Microduino Pixy摄像头SPI通讯追踪颜色/zh
(差异) ←上一版本 | 最后版本 (差异) | 下一版本→ (差异)
跳转至: 导航搜索

概述

  • 项目名称: 清华智能交通沙盘项目
  • 目的: Microduino通过SPI通讯获取Pixy颜色追踪摄像头的坐标数据,从而控制云台调整摄像头方向。
  • 难度:中级
  • 耗时:6小时
  • 制作者:


材料清单

  • Microduino设备
模块 数量 功能
Microduino-Core/zh 1 核心板
Microduino-USBTTL/zh 1 下载程序
Microduino-Duo-v/zh 1 供电底板
Microduino-Servo Connector/zh 1 舵机控制
Microduino-Sensorhub/zh 1 传感器连接板
  • 其他设备
设备 数量 功能
Pixy CMUcam5图像识别传感器模块 1 颜色追踪
云台 1 结构架
舵机 2 角度控制
MicroUSB数据线 1 供电

文档

程序下载:pixyMicroduinoServo.ino

Pixy上位机安装:pixymon_windows-2.0.6.exe

Pixy函数库:arduino_pixy-0.1.7

搭建硬件电路

  • pixy追踪摄像头
  • 上位机安装及使用

安装pixymon_windows-2.0.6.exe

  • 上位机安装完成后连接Pixy的USB数据线,此时屏幕上会出现摄像头传回的图像,电机 Action->clean all sign

清空所有标记颜色

  • 设定你要追踪的颜色

按住(不松手)右上角白色按钮直到前面的彩灯彩虹闪烁(红,橙,黄,绿,蓝,碘,紫),这时候拿一个带有饱满颜色的物体在摄像头前晃悠,电脑屏幕会标识这个物体,标识了正确的物体后再次按下白色按钮,屏幕上会次物体标识一个标签比如S1等等,你最多可以标识7个颜色的物体,这里我们只标识一个颜色。

  • 连接SPI数据线

用SPI数据线把Pixy和Microduino连接起来,由于数据线是连接Arduino的,所以你需要用跳线来改造这个数据线

引脚图:

连接好后看起来像这样

下载pixyMicroduinoServo.ino代码到Microduino Core中

打开串口你会看到摄像头初始化...

初始化完成后,这是如果你拿一个标识过的物体在摄像头前晃悠,串口会显示物体的坐标数据

这说明Pixy和Microduino通讯成功了

整体组装

安装云台

连接舵机

Microduino模块堆叠

把USB线插入Microduino-Duo-v上给Microduino供电

这时,摄像头就可以跟踪刚才那个标记过的物体了,会始终跟着物体。

接下来也可以再装一个microWrt连接一个小型摄像头方便无线看视频

具体的microWrt摄像头配置方法如下:

MicroWRT 摄像头自动启动

查看是否开启wifi etc/config 下面有个wireless

连接一个USB摄像头。同时在/dev目录下会生成设备vdieo0.

mjpeg-streamer 的执行程序在/etc/init.d 目录

设置开机启动摄像头就修改/etc/rc.local 配置文件

Vi /etc/rc.local

# Put your custom commands here that should be executed once
 # the system init finished. By default this file does nothing.
   mjpg_streamer -i "input_uvc.so -d /dev/video0 -r 640x480 -f 20" -o "output_http.so -p 8080 -w /www/webcam"
 exit 0


软件调试

程序说明

pixyMicroduinoServo.ino

#include <SPI.h>  
#include <Pixy.h>

#include <Servo.h>

Pixy pixy;

#define X_CENTER        ((PIXY_MAX_X-PIXY_MIN_X)/2)       
#define Y_CENTER        ((PIXY_MAX_Y-PIXY_MIN_Y)/2)

#define panServoPWM 8  //pwm 
#define tiltServoPWM 9  //pwm 


int panAngle=90, tiltAngle=90;
int oldPanAngle=90, oldTiltAngle=90;

int panDiff=0, tiltDiff=0;

int stepRange=3;
int gap=0;
int center=500;

Servo panServo,tiltServo;

class ServoLoop
{
public:
  ServoLoop(int32_t pgain, int32_t dgain);

  void update(int32_t error);
   
  int32_t m_pos;
  int32_t m_prevError;
  int32_t m_pgain;
  int32_t m_dgain;
};


ServoLoop panLoop(300, 500);
ServoLoop tiltLoop(500, 700);

ServoLoop::ServoLoop(int32_t pgain, int32_t dgain)
{
  m_pos = PIXY_RCS_CENTER_POS;
  m_pgain = pgain;
  m_dgain = dgain;
  m_prevError = 0x80000000L;
}

void ServoLoop::update(int32_t error)
{
  long int vel;
  char buf[32];
  if (m_prevError!=0x80000000)
  {	
    vel = (error*m_pgain + (error - m_prevError)*m_dgain)>>10;
    //sprintf(buf, "%ld\n", vel);
    //Serial.print(buf);
    m_pos += vel;
    if (m_pos>PIXY_RCS_MAX_POS) 
      m_pos = PIXY_RCS_MAX_POS; 
    else if (m_pos<PIXY_RCS_MIN_POS) 
      m_pos = PIXY_RCS_MIN_POS;
  }
  m_prevError = error;
}


void setup()
{
  Serial.begin(9600);
  Serial.print("Starting...\n");
  
  initServos();
  pixy.init();
}

void loop()
{ 
  static int i = 0;
  int j;
  uint16_t blocks;
  char buf[32]; 
  int32_t panError, tiltError;
  
  blocks = pixy.getBlocks();
  
  if (blocks)
  {
    panError = X_CENTER-pixy.blocks[0].x;
    tiltError = pixy.blocks[0].y-Y_CENTER;


    panDiff=panError;
    tiltDiff=tiltError;
    
    panLoop.update(panError);
    tiltLoop.update(tiltError);
    

    pixy.setServos(panLoop.m_pos, tiltLoop.m_pos);
    // Serial.print(panLoop.m_pos); 
    // Serial.print("\t");
    // Serial.println(tiltLoop.m_pos); 

    controlServo();

    i++;
    
    // do this (print) every 50 frames because printing every
    // frame would bog down the Arduino
    if (i%50==0) 
    {
      sprintf(buf, "Detected %d:\n", blocks);
      //Serial.print(buf);
      for (j=0; j<blocks; j++)
      {
        sprintf(buf, "  block %d: ", j);
        //Serial.print(buf); 
        //pixy.blocks[j].print();
      }
    }
  }  
}

void initServos() {
  panServo.attach(panServoPWM);
  tiltServo.attach(tiltServoPWM);

  panServo.write(panAngle);
  tiltServo.write(tiltAngle);
}


//控制舵机转动
void controlServo() {

      panAngle=map(panLoop.m_pos,0,1000,0,180);
      if(panAngle!=oldPanAngle) {
        panServo.write(panAngle);
        oldPanAngle=panAngle;
      }


      tiltAngle=map(tiltLoop.m_pos,0,1000,0,180);
      if(tiltAngle!=oldTiltAngle) {
        tiltServo.write(tiltAngle);
        oldTiltAngle=tiltAngle;
      }

    Serial.print(panAngle); 
    Serial.print("\t");
    Serial.println(tiltAngle); 
}


程序下载

  • 确认你搭建了Microduino的开发环境,否则参考:Microduino Getting start/zh
  • 确定IDE里面有arduino_pixy-0.1.7库。
  • 打开下载好的程序,编译后选择好板卡进行下载。

视频