目次

マルチプロセッサ構成

 FPGAにプロセッサを入れ、1チップ内にBrain、Leg、Eyeを
 入れてきましたが、VHDLでデジタル回路を記述できるスキル
 が必要でした。

 Arduino、PICを利用したマルチプロセッサで、Brain、Leg、Eye
 の3ブロックを別々に作成し、デバッグしやすくします。

 はじめにブロック図を作成します。



 センサーは別に用意するとして、Brain、Leg、Eyeのインタフェース
 を想定しておきます。

 ブロック図から回路図を作成。



 回路図から半田付けした基板。



 左からセンサーインタフェース(Eye)、Brain(Arduino)、DUTY比格納
 レジスタ、パルス生成(PIC)、モータ駆動FETと並べてあります。

 センサーとは、インタフェースケーブルで接続。



 センサーは、密着タイプとGameBoyCameraを接続できます。

 密着タイプセンサー



 GameBoyCamera

  GameBoyCameraは、Arduino互換器で1ライン分だけを
  出力するユニットを作成して対応。



 DCモータにパルスを出力するPIC12F1501のファームウエアは、以下。

#define OFF 0
#define ON  OFF+1

#define MASKFF 0xff
#define MMAX 63035
#define PMAX 100

typedef unsigned char UBYTE ;

#define MONC PORTA.F4

#define MPWM PORTA.F1
#define POUT PORTA.F0

volatile UBYTE pflag ;
volatile UBYTE eflag ;
volatile UBYTE pcnt ;
volatile UBYTE scnt ;
volatile UBYTE tcnt ;
volatile UBYTE mcnt ;
volatile UBYTE xcnt ;
volatile UBYTE ycnt ;

volatile UBYTE zcnt ;

/* function prototype */
void init_usr(void);

/* interrupt handler */
void interrupt(void)
{
  /* generate 2ms */
  if ( INTCON.TMR0IF == ON ) {
    /* clear flag */
    INTCON.TMR0IF = OFF ;
    /* 256 - 250 = 6 */
    TMR0 = 6 ;
    /* set flag */
    pflag = ON ;
    /* update */
    tcnt++ ;
    /* monitor */
    if ( (tcnt & ON) == ON ) { MPWM = ON ; }
    else                     { MPWM = OFF ; }
  }
  /* LTRG PORTA.F2 rising edge interrupt */
  if ( INTCON.IOCIF == ON ) {
    /* clear flag */
    IOCAF.IOCAF2 = OFF ;
    /* set event flag */
    eflag = ON ;
  }
}

void main(void)
{
  /* initialize */
  init_usr();
  /* endless loop */
  while ( ON ) {
    /* PWM wave */
    if ( pflag == ON ) {
      /* clear flag */
      pflag = OFF ;
      /* impress */
      if ( pcnt < zcnt ) { POUT = ON ; }
      else               { POUT = OFF ; }
      /* update */
      pcnt++ ;
      /* judge */
      if ( pcnt == PMAX ) {
        /* clear */
        pcnt = 0 ;
        /* update */
        zcnt = ycnt ;
      }
    }
    /* wait trigger */
    if ( eflag == ON ) {
      /* clear flag */
      eflag = OFF ;
      /* get data */
      for ( scnt = 0 ; scnt < 8 ; scnt++ ) {
        /* shift */
        xcnt <<= 1 ;
        /* add LSB */
        if ( PORTA.F5 == ON ) { xcnt |= ON ; }
        /* shift clock */
        MONC = ON ;
        MONC = OFF ;
      }
      /* update */
      ycnt = xcnt ;
    }
  }
}

/* define function body */
void init_usr(void)
{
  /* select 16MHz */
  OSCCON = (0xf << 3) | 0x03 ;
  /* disable A/D converter */
  ADCON0.ADON = OFF ;
  ADCON2      = 0 ;
  ANSELA      = 0 ;
  /* disable D/A converter */
  DACCON0 = 0 ;
  DACCON1 = 0 ;
  /* disable compare module */
  CM1CON0.C1ON = OFF ;
  CM1CON0.C1OE = OFF ;
  /* I/O state */
  PORTA = 0x00 ;
  /* I/O directions */
  TRISA = 0x2C ; /* bit0,1,4 as output , others as input */
  /* PIN change interrupt */
  {
    /* PORTA.2 rising edge */
    IOCAP.IOCAP2 = ON ;
    /* enable compare match interrupt */
    INTCON.IOCIE = ON ;
  }
  /* initialize timer 0 */
  {
    /*
       16MHz/4 = 4MHz (Fosc)
       Fosc/4 = 1MHz
       1MHz/4 = 250kHz prescaler = 1:4
    */
    OPTION_REG = 0x01 ;
    /* 256 - 250 = 6 */
    TMR0 = 6 ;
    /* enable timer0 overflow interrupt */
    INTCON.TMR0IE = ON ;
  }
  /* enable general interrupt */
  INTCON.GIE = ON ;
  /* clear flags */
  eflag = OFF ;
  pflag = OFF ;
  /* initialize variables */
  xcnt = 0 ;
  ycnt = 0 ;
  zcnt = 0 ;
  mcnt = 0 ;
  tcnt = 0 ;
  scnt = 0 ;
  pcnt = 0 ;
}

 Arduinoが、DCモータのDUTY比を8ビットシフトレジスタに
 書き込んで、その後にシフトレジスタの値を回転させながら
 PICがDUTY比を取り込みます。

 DUTY比は非同期に書き込まれるので、PIC側では更新されたのか
 判定できません。そこで、Arduinoから値を取り込むようにと
 PICにトリガーを送信します。

 PIC側では、74HC165に保存されている値を1ビットずつ8回
 入力して8ビットに仕立てます。

 PWM波形は、周波数40Hzで出力されます。

 DUTY比は、0.5%ほど変動しますが、DCモータを使う限り
 問題はないと判断しました。

 ハードウエアのテスト用スケッチは、以下。

#include <MsTimer2.h>

#define OFF 0
#define ON  OFF+1

#define MASK0F 0x0f
#define MASKF0 0xf0
#define MASKFF 0xff
#define MASK7F 0x7f

#define LED_BIT 5

#define SEL_BIT 4

#define CLK_BIT   5

#define LEFT_BIT  3
#define RIGHT_BIT 2

/* variables */
boolean uflag ;
boolean oflag ;
byte cmd ;
byte sindex ;
byte sbuf[8] ;
byte xcnt ;
byte sdat ;
byte lsensor ;
byte dleft ;
byte dright ;
char msg[4] ;
boolean tflag ;
byte tmp ;

/* function prototype */
void update_trigger();
void show_help();
void set_data(byte x);
byte get_duty(byte *ptr);
void set_duty(byte lx,byte rx);
void show_duty(byte rx);
byte get_hex(byte x);
char get_asc(byte x);
void rs_putchar(char x);
void rs_puts(char *ptr);
void crlf();
void binary_display(byte x);
byte get_sensor();
void send_trigger();
void send_shift_clk();

void setup()
{
  /* initialize serial */
  Serial.begin(9600);
  sindex = 0 ;
  /* clear flags */
  uflag  = OFF ;
  tflag  = OFF ;
  oflag  = ON ;
  /* initialize port values */
  PORTB = 0x00 ;
  PORTC = 0x0f ; /* pull up */
  PORTD = 0x0d ;
  /* initialize port direction */
  DDRB = 0xff ;
  DDRC = 0xf0 ; /* lower nibble inputs */
  DDRD = 0xfe ;
  /* clear */
  xcnt = 0 ;
  dleft = 0 ;
  dright = 0 ;
  /* 250ms period */
  MsTimer2::set(250,update_trigger);
  /* enable */ 
  MsTimer2::start();
}

void loop()
{
  /* opening message */
  if ( oflag == ON ) {
    /* new line */
    crlf();
    /* clear flag */
    oflag = OFF ;
    /* message */
    rs_puts("Hello , Darling !");
    /* new line */
    crlf();
  }
  /* serial handling */
  if ( uflag == ON ) {
    /* clear flag */
    uflag = OFF ;
    /* new line */
    crlf();
    /* get command */
    cmd = *(sbuf+0) ;
    /* help */
    if ( cmd == '?' ) { show_help() ; }
    /* set motor duty ratio */
    if ( cmd == 'D' ) {
      /* LEFT */
      dleft = get_duty( sbuf+1 );
      /* RIGHT */
      dright = get_duty( sbuf+3 );
      /* impress */
      set_duty(dleft,dright);
    }
    /* show motor duty ratio */
    if ( cmd == 'd' ) {
      /* LEFT */
      rs_puts("LEFT  = "); show_duty( dleft ); crlf();
      /* RIGHT */
      rs_puts("RIGHT = "); show_duty( dright ); crlf();
    }
    /* show sensor state */
    if ( cmd == 'S' ) {
      /* get line sensor data */
      tmp = lsensor ;
      /* binary display */
      binary_display( tmp );
      /* new line */
      crlf();
      /* start gate */
      if ( tflag == ON ) { rs_puts("Opened"); }
      else               { rs_puts("Closed"); }
      /* new line */
      crlf();
    }
    /* command */
    if ( cmd == 'C' ) { send_trigger(); }
  }
}

void update_trigger()
{
  /* get sensor state */
  sdat = get_sensor() ;
  sdat ^= MASKFF ;
  /* start trigger */
  tflag = OFF ;
  if ( !(sdat & 16) ) { tflag = ON ; }
  /* line sensor */
  lsensor = ((sdat >> 1) & MASKF0) | (sdat & MASK0F) ;
  /* impress */
  if ( xcnt & 1 ) { PORTB |=  (1 << LED_BIT); }
  else            { PORTB &= ~(1 << LED_BIT); }
  /* increment */
  xcnt++ ;
}

void show_help()
{
  rs_puts("? help");                  crlf();
  rs_puts("D set motor duty ratio");  crlf();
  rs_puts("d show motor duty ratio"); crlf();
  rs_puts("S show sensor state");     crlf();
  rs_puts("C send command");          crlf();
}

void  set_data(byte x)
{
  byte dh ;
  byte dl ;
  /* separate */
  dh = x & MASKF0 ;
  dl = x & MASK0F ;
  /* upper */
  PORTD &= MASK0F ;
  PORTD |= dh ;
  /* lower */
  PORTB &= MASKF0 ;
  PORTB |= dl ;
}

byte get_duty(byte *ptr)
{
  byte result ;
  /* upper */
  result = get_hex( *ptr );
  /* shift */
  result *= 10 ;
  /* lower */
  result += get_hex( *(ptr+1) );
  /* range check */
  if ( result > 99 ) { result = 99 ; }

  return result ;
}

void  set_duty(byte lx,byte rx)
{
  /* left */
  set_data(lx) ;
  PORTD &= ~(1 << LEFT_BIT);
  PORTD |= (1 << LEFT_BIT);
  /* right */
  set_data(rx) ;
  PORTD &= ~(1 << RIGHT_BIT);
  PORTD |= (1 << RIGHT_BIT);
}

void show_duty(byte x)
{
  /* delimiter */
  *(msg+2) = '\0' ;
  /* separate */
  *(msg+1) = get_asc( x % 10 );
  *(msg+0) = get_asc( x / 10 );
  /* show */
  rs_puts( msg );
}

byte  get_hex(byte x)
{
  byte result ;
  /* default */
  result = 0 ;
  /* judge */
  if ( '0' <= x && x <= '9' ) { result = x - '0' ; }
  if ( 'A' <= x && x <= 'F' ) { result = x - 'A' + 10 ; }
  if ( 'a' <= x && x <= 'f' ) { result = x - 'a' + 10 ; }
  
  return result ;
}

void rs_putchar(char x)
{
  Serial.write(x);
}

void rs_puts(char *ptr)
{
  while ( *ptr ) {
    rs_putchar( *ptr );
    ptr++;
  }
}

void crlf()
{
  rs_putchar('\r');
  rs_putchar('\n');
}

char get_asc(byte x)
{
  char result ;
  /* default */
  result = '0' ;
  /* convert */
  if ( x < 10 ) { result = x + '0' ; }
  if ( 9 < x && x < 16 ) { result = x - 10 + 'A' ; }

  return result ;
}

void binary_display(byte x)
{
  int i ;
  for ( i = 7 ; i > -1 ; i-- ) {
    rs_putchar('0'+((x >> i) & 1));
  }
}

byte get_sensor()
{
  byte dh ;
  byte dl ;
  byte xtmp ;
  /* upper */
  PORTC |= (1 << SEL_BIT);
  dh = PINC & MASK0F ;
  dh <<= 4 ;
  dh &= MASKF0 ;
  /* lower */
  PORTC &= ~(1 << SEL_BIT);
  dl = PINC & MASK0F ;
  /* concatenate */
  xtmp = dh | dl ;
  /* inverse */
  xtmp = ( xtmp & 0x55 ) << 1 | ( xtmp & 0xAA ) >> 1;
  xtmp = ( xtmp & 0x33 ) << 2 | ( xtmp & 0xCC ) >> 2;
  xtmp = ( xtmp & 0x0F ) << 4 | ( xtmp & 0xF0 ) >> 4;

  return xtmp ;
}

void send_trigger()
{
  PORTC |= (1 << CLK_BIT);
  delayMicroseconds(5);
  PORTC &= ~(1 << CLK_BIT);
  delayMicroseconds(5);
}

/* receive interrupt */
void serialEvent()
{
  char ch;
  if ( Serial.available() > 0 ) {
    /* get 1 character */
    ch = Serial.read();
    /* store */
    *(sbuf+sindex) = ch ;
    /* increment */
    sindex++ ;
    /* judge */
    if ( ch == '\r' ) {
      sindex = 0 ; 
      uflag  = ON ;
    }
  }
}

 Arduinoに対してDUTY比を与え、PICに転送する操作は
 端末ソフトでチェックしました。



 74HC165+PIC12F1501ではなく、Arduinoに標準で用意された
 PWMモジュールを使う場合、次のスケッチで確認できます。

#include <MsTimer2.h>

#define OFF 0
#define ON  OFF+1

#define MASK0F 0x0f
#define MASKF0 0xf0
#define MASKFF 0xff
#define MASK7F 0x7f

#define LED_BIT 5

#define SEL_BIT 4

#define LEFT_BIT  6
#define RIGHT_BIT 5

#define MOVE_NONE   0
#define MOVE_NORMAL NONE+1
#define MOVE_CRANK  NONE+2
#define MOVE_ROTATE NONE+3
#define MOVE_LANE   NONE+4
#define MOVE_CHANGE NONE+5
#define MOVE_BLIND  NONE+6

/* variables */
boolean uflag ;
boolean oflag ;
byte cmd ;
byte sindex ;
byte sbuf[8] ;
byte xcnt ;
byte sdat ;
byte lsensor ;
byte dleft ;
byte dright ;
char msg[4] ;
boolean tflag ;
byte tmp ;

/* function prototype */
void update_trigger();
void show_help();
byte get_duty(byte *ptr);
void set_duty(byte lx,byte rx);
void show_duty(byte rx);
byte get_hex(byte x);
char get_asc(byte x);
void rs_putchar(char x);
void rs_puts(char *ptr);
void crlf();
void binary_display(byte x);
byte get_sensor();

void setup()
{
  /* initialize serial */
  Serial.begin(9600);
  sindex = 0 ;
  /* clear flags */
  uflag  = OFF ;
  tflag  = OFF ;
  oflag  = ON ;
  /* initialize port values */
  PORTB = 0x00 ;
  PORTC = 0x0f ; /* pull up */
  PORTD = 0x0d ;
  /* initialize port direction */
  DDRB = 0xff ;
  DDRC = 0xf0 ; /* lower nibble inputs */
  DDRD = 0xfe ;
  /* clear */
  xcnt = 0 ;
  dleft = 0 ;
  dright = 0 ;
  /* 250ms period */
  MsTimer2::set(250,update_trigger);
  /* enable */ 
  MsTimer2::start();
}

void loop()
{
  /* opening message */
  if ( oflag == ON ) {
    /* new line */
    crlf();
    /* clear flag */
    oflag = OFF ;
    /* message */
    rs_puts("Hello , Darling !");
    /* new line */
    crlf();
  }
  /* serial handling */
  if ( uflag == ON ) {
    /* clear flag */
    uflag = OFF ;
    /* new line */
    crlf();
    /* get command */
    cmd = *(sbuf+0) ;
    /* help */
    if ( cmd == '?' ) { show_help() ; }
    /* set motor duty ratio */
    if ( cmd == 'D' ) {
      /* LEFT */
      dleft = get_duty( sbuf+1 );
      /* RIGHT */
      dright = get_duty( sbuf+3 );
      /* impress */
      set_duty(dleft,dright);
    }
    /* show motor duty ratio */
    if ( cmd == 'd' ) {
      /* LEFT */
      rs_puts("LEFT  = "); show_duty( dleft ); crlf();
      /* RIGHT */
      rs_puts("RIGHT = "); show_duty( dright ); crlf();
    }
    /* show sensor state */
    if ( cmd == 'S' ) {
      /* get line sensor data */
      tmp = lsensor ;
      /* binary display */
      binary_display( tmp );
      /* new line */
      crlf();
      /* start gate */
      if ( tflag == ON ) { rs_puts("Opened"); }
      else               { rs_puts("Closed"); }
      /* new line */
      crlf();
    }
  }
}

void update_trigger()
{
  /* get sensor state */
  sdat = get_sensor() ;
  sdat ^= MASKFF ;
  /* start trigger */
  tflag = OFF ;
  if ( !(sdat & 16) ) { tflag = ON ; }
  /* line sensor */
  lsensor = ((sdat >> 1) & MASKF0) | (sdat & MASK0F) ;
  /* impress */
  if ( xcnt & 1 ) { PORTB |=  (1 << LED_BIT); }
  else            { PORTB &= ~(1 << LED_BIT);  }
  /* increment */
  xcnt++ ;
}

void show_help()
{
  rs_puts("? help");                  crlf();
  rs_puts("D set motor duty ratio");  crlf();
  rs_puts("d show motor duty ratio"); crlf();
  rs_puts("S show sensor state");     crlf();
}

byte get_duty(byte *ptr)
{
  byte result ;
  /* upper */
  result = get_hex( *ptr );
  /* shift */
  result *= 10 ;
  /* lower */
  result += get_hex( *(ptr+1) );
  /* range check */
  if ( result > 99 ) { result = 99 ; }

  return result ;
}

void  set_duty(byte lx,byte rx)
{
  word ll ;
  word rr ;
  /* left */
  ll = (byte)((256.0 * lx) / 100);
  /* right */
  rr = (byte)((256.0 * rx) / 100);
  /* impress */
  analogWrite(LEFT_BIT,ll);
  analogWrite(RIGHT_BIT,rr);
}

void show_duty(byte x)
{
  /* delimiter */
  *(msg+2) = '\0' ;
  /* separate */
  *(msg+1) = get_asc( x % 10 );
  *(msg+0) = get_asc( x / 10 );
  /* show */
  rs_puts( msg );
}

byte  get_hex(byte x)
{
  byte result ;
  /* default */
  result = 0 ;
  /* judge */
  if ( '0' <= x && x <= '9' ) { result = x - '0' ; }
  if ( 'A' <= x && x <= 'F' ) { result = x - 'A' + 10 ; }
  if ( 'a' <= x && x <= 'f' ) { result = x - 'a' + 10 ; }
  
  return result ;
}

void rs_putchar(char x)
{
  Serial.write(x);
}

void rs_puts(char *ptr)
{
  while ( *ptr ) {
    rs_putchar( *ptr );
    ptr++;
  }
}

void crlf()
{
  rs_putchar('\r');
  rs_putchar('\n');
}

char get_asc(byte x)
{
  char result ;
  /* default */
  result = '0' ;
  /* convert */
  if ( x < 10 ) { result = x + '0' ; }
  if ( 9 < x && x < 16 ) { result = x - 10 + 'A' ; }

  return result ;
}

void binary_display(byte x)
{
  int i ;
  for ( i = 7 ; i > -1 ; i-- ) {
    rs_putchar('0'+((x >> i) & 1));
  }
}

byte get_sensor()
{
  byte dh ;
  byte dl ;
  byte xtmp ;
  /* upper */
  PORTC |= (1 << SEL_BIT);
  dh = PINC & MASK0F ;
  dh <<= 4 ;
  dh &= MASKF0 ;
  /* lower */
  PORTC &= ~(1 << SEL_BIT);
  dl = PINC & MASK0F ;
  /* concatenate */
  xtmp = dh | dl ;
  /* inverse */
  xtmp = ( xtmp & 0x55 ) << 1 | ( xtmp & 0xAA ) >> 1;
  xtmp = ( xtmp & 0x33 ) << 2 | ( xtmp & 0xCC ) >> 2;
  xtmp = ( xtmp & 0x0F ) << 4 | ( xtmp & 0xF0 ) >> 4;

  return xtmp ;
}

/* receive interrupt */
void serialEvent()
{
  char ch;
  if ( Serial.available() > 0 ) {
    /* get 1 character */
    ch = Serial.read();
    /* store */
    *(sbuf+sindex) = ch ;
    /* increment */
    sindex++ ;
    /* judge */
    if ( ch == '\r' ) {
      sindex = 0 ; 
      uflag  = ON ;
    }
  }
}


目次

inserted by FC2 system