15.おまけ


特別製IRセンサ高速版機能追加
EEPROMに音データを入れる
各種音楽データをEEPROMから読みだして演奏する
EEPROM音符データを用いるように変更

特別製IRセンサ高速版機能追加

IRセンサの間隔を広くして、高速走行できるようにします。特製IRセンサを取り付け電源を入れるとコンピュータは以前のIRセンサであると判断します。特製IRセンサのプログラムを動かすには、電源を入れた後でプッシュボタンを長押しして、設定モード移行後、一度プッシュボタンを押して赤が点灯して一秒程度放置すると青のLED点滅になりますが、その直前にIRセンサの初期設定がされますので、赤LED点灯後すぐに白レベルを読ませる状況にしてください。

以下のプログラムをコピーして、貼り付けてください。

「特別製IRセンサ高速版機能追加」プログラム
// ファイル名 RobotFast.c
// 外部センサオプション番号を判別してライントレースとマイク、手かざし動作を実行する。
// 明るさ設定は電源投入時直後に白レベルを読み取る。
// マイクの時間待ちに音楽を流す
// プッシュスイッチでプログラム選択可能にした。
// ランダムウォークを付け加えた
// 特別製IRセンサ高速版機能追加(LineTrace2())
// チャイム音を追加
//  LED の色
//      0:黒、1:赤、2:青、3:紫、4:緑、5:黄、6:水色、7:白

#include <htc.h>
__CONFIG(PWRTEN&HS&WDTDIS&UNPROTECT&MCLRDIS&BORDIS&IESODIS&FCMDIS);

#define _XTAL_FREQ 20000000
#define PERIOD 100
#define false 0
#define true  1
#define AN4   0x91
#define AN5   0x95
#define AN6   0x99
#define AN7   0x9d
#define AN10  0xa9
#define AN11  0xad
#define ABS(x) ((x>=0) ? (x) : -(x))
#define FirstPeriod 64345
#define SLOW  35
#define  LOW  40
#define MIDDLE 80
#define MIDDLE1 100
#define MIDDLE2 120
#define HIGH  160
#define StopState 8

typedef unsigned char byte;

void LED(byte n, byte times);
void Delay50();
void Delay100();
void Delay500();
void initialize();
void setIRThreshold(byte th);
byte checkIR();
void LineTrace();
void LineTrace2();
byte getOption();
void getAD(byte channel, byte* flag);
void Mic();
void setInterrupt();
byte checkCdS();
void setThreshold(byte th);
void overHand();
void SoundPlay(unsigned tone, byte dulation);
void musicPlay(byte tones[], byte speed);
byte progSW();
byte setOption();
void randomWalk();

// グローバル変数の宣言
byte counter=0;
byte LeftCdS, CenterCdS, RightCdS,ExRCdS;
byte threshold[4];
byte ADch=0;
byte ConvEndFlag;
byte ADC[4]={AN4,AN5,AN11,AN6};
byte Leftspeed=208;
byte Centerspeed=208;
byte Rightspeed=208;
byte CdSInt;
byte neko[]={8,14,12, 5, 5,17,255,17,255};
byte chime[]={11,21,5,19,12,255,12,19,21,17,17,255};

// 割り込み処理ルーチン
void interrupt Intr(void)
{
  // 約2ms毎に割り込む
  if(T0IF) {                  // 割り込みがtimer0からか?
    counter++;
    TMR0 = PERIOD;
    T0IF = 0;                 // 割り込みフラグクリア
    return;
  }
  if(ADIF) {                  // 割り込みがADコンバーターからか?
    if(CdSInt) {              // それはCdS使用か?
      if(ADch==0) LeftCdS = ADRESH;
      else if(ADch==1) CenterCdS = ADRESH;
      else if(ADch==2) RightCdS = ADRESH;
    }
    else {  
      if(ADch==0) LeftCdS = ADRESL;
      else if(ADch==1) CenterCdS = ADRESL;
      else if(ADch==2) RightCdS = ADRESL;
      else if(ADch==3) ExRCdS = ADRESL;
    }
    ConvEndFlag=true;         // データの更新あり
    ADIF = 0;                 // 割り込みフラグクリア
  }
}

main()
{
  int st;
  byte state=0;
  
  initialize(); 
  state = setOption();        // 外部センサオプション番号を設定
  setInterrupt();             // タイマーとADの割り込み設定
  GODONE = 1;                 // AD変換スタート
  while(true) {
    switch(state) {
      case 1: LineTrace2(); break;  // 赤
      case 2: LineTrace(); break; // 青 
      case 3: randomWalk();break; // 紫      
      case 4: musicPlay(neko, 3); // 緑
              musicPlay(neko, 3); // 緑
              state = StopState; 
                           break;
      case 5: musicPlay(chime, 7);// 黄
              state = StopState; 
                           break;
      case 6: overHand();  break; // 水 CdSで手かざしで動かす
      case 7: Mic();       break; // 白
      case StopState: 
              PORTC &= 0x0f;      // モーター停止
              break;
      default:randomWalk();break;
    }
    st = modeSelect();            // プッシュスイッチでの状態変更
    if(st != -1) state = st;
  }
}

byte setOption()
{
  int i;
  byte state=0;
  byte extOption;                 // 外部センサオプション番号
  extOption = getOption();
  if((extOption & 0x3f)==0x38) {      // マイクモード
    state=7;
    LED(state,5);
    musicPlay(neko, 3);               // 時間稼ぎ
    musicPlay(neko, 3);
    CdSInt = false;
  }
  else if((extOption & 0x38)==0x20) { // 手かざしモード
    state=6;
    LED(state, 5);                    // 水色
    CdSInt = true;
    setThreshold(65);                 // 白レベルの値から閾値(65%)に決める
  }
  else if((extOption & 0x18)==0x10) { // photo refrector
    setIRThreshold(13);               // ライントレース
    state=2; 
    LED(state, 5);                    // 青
    CdSInt = false;
  }
  return state;
}  

int modeSelect()
{
  int longPush=0;
  byte st;
  Delay100(); 
  while(!RA3) {                   // まだ押されていたら
    if(counter==0) {
      if(longPush++==200) {       // 長押しだったら
        PORTC &= 0x0f;            // motor stop
        SoundPlay(52, 1);
        Delay50();
        SoundPlay(52, 1);
        LED(7,2);
        st = progSW();
        if(st != 0) return st;
      }
    }
  } 
  return -1;
}

void setInterrupt()
{ 
  // Timer0 の設定
  T0IE=1;                     // Timer0 の割り込みON
  T0IF=0;                     // 割り込みフラグクリア
  
  // ADコンバーターの設定
  ADIE = 1;                   // ADコンバータの割り込み許可
  ADIF = 0;                   // 割り込みフラグクリア
  PEIE = 1;                   // 周辺装置の割り込み許可
  GIE  = 1;                   // CPUへの割り込み許可
}
    
void initialize()
{
  PORTA = 0;                  // PORTAを0にする
  TRISA = 0;                  // PORTAを出力に設定する
  TRISB = 0x30;               // 4,5input
  PORTB = 0;
  PORTC = 0;                  // PORTCを0にする
  TRISC = 0x0f;               // PORTC下4bit入力、上4bit出力
  ANSEL = 0xF0;               // AN4,5,6,7 ON
  ANSELH = 0x0C;              // AN10,11 ON
  ADCON0 = AN4;               // ADFM=1(右詰)  AN4 adOn
                              // 1 = Right justified
  OPTION = 0;
                              // 1:8 prescale
  T1CON = 0x31;               // Timer1 settings
  TMR1IF = 0;                 // clear TMR1IF
  TMR1H = 0xf8;               // Initialize Timer1 register
  TMR1L = 0x00;

  ADC[0]=AN4;
  ADC[1]=AN5;
  ADC[2]=AN6;
  ADC[3]=AN11;
  
  CdSInt = false;             // CdSは付いていない
}

void LineTrace()
{
  while(RA3)
  { 
    switch(checkIR()){
      case 15:
      case 6: Rightspeed=Leftspeed=MIDDLE2;  // 直進   青
              RC5=0; RC7=0;
              break;
      case 14:
      case 12: Rightspeed = MIDDLE2; Leftspeed = 60; //左に行く 紫
              RC5=0; RC7=0;
              break;
      case 8: Rightspeed = MIDDLE2; Leftspeed = ~LOW;  //左に行く 赤
              RC5=0; RC7=1;
              break;
      case 7:
      case 3: Rightspeed = 60;  Leftspeed = MIDDLE2;   // 水色
              RC5=0; RC7=0;
              break;
      case 1: Rightspeed = ~LOW;  Leftspeed = MIDDLE2;    //  緑
              RC5=1; RC7=0;
              break;
    } // switch
   
    RC4 = counter < Rightspeed;
    RC6 = counter < Leftspeed;

  
  }  // while
}

void LineTrace2()
{ 
  setOption();  
  while(RA3){
    switch(checkIR()){
      
      case 6: Rightspeed=Leftspeed=240;  // 直進
              RC5=0; RC7=0;
              break;            
      case 2: Rightspeed = 140;  Leftspeed = 240;   // 右に行く
              RC5=0; RC7=0;
              break;
      case 1: Rightspeed = 50;  Leftspeed = 240;   // 右に行く
              RC5=0; RC7=0;
              break;
      case 8:
              Rightspeed = 240; Leftspeed = 50; //左に行く 
              RC5=0; RC7=0;
              break; 
      case 4: Rightspeed = 240; Leftspeed = 140; //左に行く 
              RC5=0; RC7=0;
              break;     
    } // switch
    RC4 = (counter<Rightspeed)?1:0;
    RC6 = (counter<Leftspeed)?1:0;

  }  // while
}

void LED(byte n, byte times)
{
  byte i;
  for(i=0; i<times; i++) {
    PORTA =  n;
    Delay50();                // 50msディレイ
    PORTA =  0;
    Delay50();                // 50msディレイ
  }
}

void Delay50()                // 50m秒ディレイ
{
  int i;
  for(i=0; i<5; i++)        
    __delay_ms(10); 
}

void Delay100()               // 100m秒ディレイ
{
  int i;
  for(i=0; i<10; i++)        
    __delay_ms(10); 
}

void Delay500()               // 500m秒ディレイ
{
  int i;
  for(i=0; i<50; i++)        
    __delay_ms(10); 
}

void setIRThreshold(byte th)
{
  byte i, j, x;
  int average[4]={0,0,0,0};
  GIE=0;
 // 明るいときの値 明るいと大きい値
  ADC[0]=AN4;
  ADC[1]=AN5;
  ADC[2]=AN6;
  ADC[3]=AN11;
  for(j=0; j<40; j++) {
    for(i=0; i<4; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESL;
      average[i] = (average[i]*9+x)/10;
    }
  }
  for(i=0; i<4; i++)
    threshold[i]=average[i]*th/20;
  GIE=1;
}

byte checkIR()
{
  byte status;

  if(ConvEndFlag) { // AD変換が終わったらすぐに次のチャンネルの変換を行う
    ConvEndFlag = false;
    if(++ADch==4) ADch=0;
    ADCON0 = ADC[ADch];  // 変換スタート
    GODONE = 1;
  }
  PORTA=0;
  status = 0;

  RA2 = ExRCdS<threshold[3];
  RA1 = RightCdS<threshold[2];
  RA0 = CenterCdS<threshold[1];

  status =  RA2;
  status += RA1 ? 2 : 0;
  status += RA0 ? 4 : 0;
  status += LeftCdS<threshold[0] ? 8 : 0;

  return status;
}

#define optTH 100

byte getOption()
{
  byte flag;
  byte x;

  getAD(AN4,&flag);
  getAD(AN5, &x);
  if(x) flag|=2;
  getAD(AN6, &x);
  if(x) flag|=4;
  getAD(AN7, &x);
  if(x) flag|=8;
  getAD(AN10, &x);
  if(x) flag|=0x10;
  getAD(AN11, &x);
  if(x) flag|=0x20;
  return flag;
}

void getAD(byte channel, byte* flag)
{
  int x;
  ADCON0 = channel;
  GODONE = 1;
  while(GODONE);
  x = ADRESH;
  x = x*256+ADRESL;
  *flag = x > optTH;
}


#define MICTH 4
#define MIDLOW 80
void Mic()
{
  byte i;
  int average[3]={185,185,185};
  int average2[3]={185,185,185};
  int x,y,diff[3];
  byte a,b,c,max;
  unsigned int cnt=0;
  
  GIE=0;
  ADC[0]=AN7;
  ADC[1]=AN10;
  ADC[2]=AN11;
  for(cnt=0; cnt<1000; cnt++) {
    for(i=0; i<3; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESL;
      average[i] = (average[i]*9+x)/10;
      if(x > average[i])
        average2[i] = (average2[i]*11+x)/12;
    }
  }
  // 半永久ループ
  while(RA3){  // スイッチが押されたら抜ける
    for(i=0; i<3; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESL;
      average[i] = (average[i]*9+x)/10;
      if(x > average[i])
        average2[i] = (average2[i]*11+x)/12;
      diff[i] = average2[i] - average[i];
    }
    if((diff[0] >MICTH) || (diff[1]>MICTH) || 
        (diff[2]>MICTH)) {
      a=diff[0]; b=diff[1]; c=diff[2];
      if(a>b) {
        if(a>c) { max=0; }
        else    { max=2;}
      }
      else if(b>c) { max = 1; }
      else { max=2; }

      GIE=1;
      x=500;       // 回転カウント
      switch(max){
        case 2: // Left
              PORTA = 4;
              Rightspeed = ~MIDLOW;  Leftspeed = MIDLOW;
              RC5=1; RC7=0;
              break;
        case 1: // backward
              PORTA = 2;
              if(diff[1]&1){  // たまに逆回りする
                Rightspeed = ~MIDLOW;  Leftspeed = MIDLOW;
                RC5=1; RC7=0;
              }
              else {
                Rightspeed = MIDLOW;  Leftspeed = ~MIDLOW;
                RC5=0; RC7=1;
              }
              x = 700;
              break;
        case 0: // Right
              PORTA = 1;
              Rightspeed = MIDLOW; Leftspeed = ~MIDLOW;
              RC5=0; RC7=1;
              break;
        default:
              PORTC &= 0x0f;
      }
      counter=0;
      cnt=0;
      while(cnt!=x) {
        if(counter==0) cnt++;
        RC4 = counter < Rightspeed;
        RC6 = counter < Leftspeed;
        if(!RA3) return;
      }
      PORTC &= 0x0f;
      PORTA = 0;
      GIE=0;
      Delay100();
      for(cnt=0; cnt<500; cnt++) {
        for(i=0; i<3; i++) {
          ADCON0 = ADC[i];
          GODONE = 1;
          while(GODONE);
          x = ADRESL;
          average[i] = (average[i]*9+x)/10;
        }
      } 
      for(i=0; i<3; i++) average2[i] = average[i];

    } //if
  }
  GIE=1;
}

byte checkCdS()
{
  byte status;

  if(ConvEndFlag) { // AD変換が終わったらすぐに次のチャンネルの変換を行う
    ConvEndFlag = false;
    if(++ADch==3) ADch=0;
      ADCON0 = ADC[ADch];     // ADチャンネル変更
      GODONE = 1;             // AD変換スタート
  }
    
  PORTA=0;
  RA2 = RightCdS  < threshold[2];  // 赤
  RA1 = CenterCdS < threshold[1];  // 緑
  RA0 = LeftCdS   < threshold[0];  // 青
  
  status = RA2;
  status += RA1 ? 2 : 0;
  status += RA0 ? 4 : 0;
  return status;
}

void setThreshold(byte th)    // 平均の指定%を閾値にする
{
  byte i, j, x, g;
  int average[3]={0,0,0};
  g = GIE;                    // 割り込み状態の保存
  GIE=0;                      // 割り込みは使わない
 // 明るいときの値 明るいと大きい値
  ADC[0]=AN4&0x7f;
  ADC[1]=AN5&0x7f;
  ADC[2]=AN6&0x7f;
  for(j=0; j<40; j++) {       // 平均の明るさを求める
    for(i=0; i<3; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESH;
      average[i] = (average[i]*9+x)/10;
    }
  }
  for(i=0; i<3; i++)
    threshold[i]=average[i]*th/100;
  GIE = g;                    // CPUへの割り込み状態を戻す
}

void overHand()
{
  while(RA3){
    switch(checkCdS()) {
      case 7: Rightspeed=Leftspeed=MIDDLE;    // 直進
              RC5 = RC7 = 0;
              break;
      case 6: Rightspeed = LOW;  Leftspeed = MIDDLE;
              RC5 = 0; RC7 = 0;
              break;
  
      case 4: Rightspeed = ~MIDDLE;  Leftspeed = MIDDLE;
              RC5 = 1; RC7 = 0;
              break;
      case 3: Rightspeed = MIDDLE; Leftspeed = LOW;
              RC5 = 0; RC7 = 0;
              break;
      case 1: Rightspeed = MIDDLE; Leftspeed = ~MIDDLE;
              RC5 = 0; RC7 = 1;
              break;
      case 2:
              Rightspeed=Leftspeed=~MIDDLE;
              RC5 = RC7 = 1;
              break;
      default:
      case 0: Rightspeed=Leftspeed=255;
              RC5 = RC7 = 1;
              break;
    }
    RC4 = counter<Rightspeed;
    RC6 = counter<Leftspeed;
  }  
}

byte diff[]={    // 1191
67,63,59,57,53,50,47,45,42,40,37,35,
34,31,30,28,27,25,24,22,21,20,19,17,
17,16,15,14,13,12,12,11,11,10, 9, 9,
 8, 8, 8, 7, 6, 7, 6, 5, 5, 5, 5, 5,
 4, 4, 3, 4};

void SoundPlay(unsigned tone, byte dulation)
{
   unsigned i, peri, n;
   byte j, k=0;
   byte H, L;
   unsigned term;
   unsigned all  = 1191;//0xffff-FirstPeriod+1;
   peri = FirstPeriod;
   if(tone == 255) {
      tone = 0;
      k = 1;
   }
   for(j=0; j<tone; j++) peri += diff[j];
   term = 0xffff-peri+1;
   n = 4*dulation*all/term*10;
   H = peri >> 8;
   L = peri & 0xff;
   for(i=0; i<n; ) {
     if(TMR1IF) {
       if(!k) PORTB = ~PORTB;
       TMR1H = H;               // Initialize Timer1 register
       TMR1L = L;
       TMR1IF = 0;
       i++;
    }
  }
}

void musicPlay(byte tones[], byte speed)
{
  byte m, j;
  unsigned int i;

  m = tones[0];
  for(i=1; i<=m; i++) SoundPlay(tones[i], speed);
}

byte progSW(){
  byte on=0;
  byte state=0;
  int t=0;
  Delay500();
  while(true){
    if(!RA3) {     // 押されたら
      Delay100() ;
      on = true;
      t=0;
    }
    if(on && RA3) {
      on = false;
      if(++state==8) state=0;
      //SoundPlay(52, 1);
      LED(state, 1);
      t=0;
    }
    if(counter++==0) {
      if(t++==1000) return state;    // 0も返す
    }
  }
}

void randomWalk()
{
  byte timer=0;
  while(RA3) {
    if(counter==0) {
      if(timer++==200) {
        timer = 0;
        switch(rand()&7){
          case 0: Rightspeed=Leftspeed=HIGH;  // 直進
                  RC5 = RC7 =0; break;
          case 1: Rightspeed = HIGH; Leftspeed = SLOW;
                  RC5 = RC7 =0; break;
          case 2: Rightspeed = SLOW;  Leftspeed = HIGH;
                  RC5 = RC7 =0; break;
          case 3: Rightspeed=Leftspeed=~HIGH;  // 後進
                  RC5 = RC7 = 1; break;
          case 4: Rightspeed = ~HIGH; Leftspeed = ~SLOW;
                  RC5 = RC7 = 1; break;
          case 5: Rightspeed = ~SLOW;  Leftspeed = ~HIGH;
                  RC5 = RC7 = 1; break;
          case 6: Rightspeed = HIGH; Leftspeed = LOW;
                  RC5 = RC7 = 0; break;
          case 7: Rightspeed = LOW;  Leftspeed = HIGH;
                  RC5 = RC7 = 0; break;
        }
      }
    }
    RC4 = counter < Rightspeed;
    RC6 = counter < Leftspeed;
  }
}

EEPROMに音データを入れる

今までは、PIC内のFlashRomにデータを入れていましたが、PICにはさらにEEPROMというデータの読み書きができるメモリが存在しています。これを利用しないわけにはいかないので音符データを入れるにはもってこいなので、これを使います。
先ずは、音階データを入れて再生実験です。

EEPROMに音データを入れる
// ファイル名 toneRom.c
// EEPROMに音階データを入れて4オクターブ鳴らしてみる
#include <htc.h>
__CONFIG(PWRTEN&HS&WDTDIS&UNPROTECT&MCLRDIS&BORDIS&IESODIS&FCMDIS);

#define _XTAL_FREQ 20000000
#define ANS4 0x10
#define FirstPeriod 64345

typedef unsigned char byte;

void SoundPlay(unsigned tone, byte dulation);
byte tone[29];
__EEPROM_DATA( 4, 6, 8, 9,11,13,15,16);
__EEPROM_DATA(18,20,21,23,25,27,28,30);
__EEPROM_DATA(32,33,35,37,39,40,42,44);
__EEPROM_DATA(45,47,49,51,52, 0, 0, 0);

main()
{
  int i;

  OPTION = 3;                 // FOSC/4 プリスケーラ1/16
  T1CON = 0x31;               // Timer1 settings
  TMR1IF = 0;                 // clear TMR1IF
  TMR1H = 0xf8;               // Initialize Timer1 register
  TMR1L = 0x00;
  TRISB = 0x00;               // スピーカー
  PORTB = 0;

  for(i=0; i<29; i++) tone[i]=eeprom_read(i);
  while(1) {
    for(i=0; i<29; i++) 
      SoundPlay(tone[i], 5);
  }
}

byte diff[]={    // 1191
67,63,59,57,53,50,47,45,42,40,37,35,
34,31,30,28,27,25,24,22,21,20,19,17,
17,16,15,14,13,12,12,11,11,10, 9, 9,
 8, 8, 8, 7, 6, 7, 6, 5, 5, 5, 5, 5,
 4, 4, 3, 4};

void SoundPlay(unsigned tone, byte dulation)
{
   unsigned i, peri, n;
   byte j, k=0;
   byte H, L;
   unsigned term;
   unsigned all  = 1191;//0xffff-FirstPeriod+1;
   peri = FirstPeriod;
   if(tone == 255) {    // 255 は休符
      tone = 0;
      k = 1;
   }
   for(j=0; j<tone; j++) peri += diff[j];
   term = 0xffff-peri+1;
   n = 4*dulation*all/term*10;
   H = peri >> 8;
   L = peri & 0xff;
   for(i=0; i<n; ) {
     if(TMR1IF) {
       if(!k) PORTB = ~PORTB;
       TMR1H = H;               // Initialize Timer1 register
       TMR1L = L;
       TMR1IF = 0;
       i++;
    }
  }
}

__EEPROM_DATA( 4, 6, 8, 9,11,13,15,16);
EEPROMにバイトデータを入れるマクロです。書き込み時に実行されます。
eeprom_read(i);
EEPROMからi番目のバイトデータを読み込む関数です。

各種音楽データをEEPROMから読みだして演奏する

実際に使うメロディデータを書き込み、これを読みだして再生するようにします。
最初のバイトはその曲のバイト数を書き入れるという書式にします。

各種音楽データをEEPROMから読みだして演奏する
// ファイル名 toneMusic.c
// 各種音楽データをEEPROMから読みだして演奏する
#include <htc.h>
__CONFIG(PWRTEN&HS&WDTDIS&UNPROTECT&MCLRDIS&BORDIS&IESODIS&FCMDIS);

#define _XTAL_FREQ 20000000
#define ANS4 0x10
#define FirstPeriod 64345

#define Neko     0x00
#define Chime    0x0a
#define Funeral  0x16
#define Flog     0x3b

typedef unsigned char byte;

void SoundPlay(unsigned tone, byte dulation);
void musicPlay(byte n, byte speed);
void Delay500();

byte tones[36];
__EEPROM_DATA(0x08, 0x0e, 0x0c, 0x05, 0x05, 0x11, 0xff, 0x11);
__EEPROM_DATA(0xff, 0xff, 0x0b, 0x15, 0x05, 0x13, 0x0c, 0xff);
__EEPROM_DATA(0x0c, 0x13, 0x15, 0x11, 0x11, 0xff, 0x24, 0x05);
__EEPROM_DATA(0x05, 0x05, 0xff, 0x05, 0x05, 0x05, 0xff, 0x05); 
__EEPROM_DATA(0xff, 0x05, 0x05, 0x05, 0xff, 0x08, 0x08, 0x08);
__EEPROM_DATA(0xff, 0x07, 0xff, 0x07, 0x07, 0x07, 0xff, 0x05);  
__EEPROM_DATA(0xff, 0x05, 0x05, 0x05, 0xff, 0x04, 0xff, 0x05);
__EEPROM_DATA(0x05, 0x05, 0x05, 0x10, 0x03, 0x05, 0x07, 0x08);  
__EEPROM_DATA(0x07, 0x05, 0x03, 0xff, 0x07, 0x08, 0x0a, 0x0c);  
__EEPROM_DATA(0x0a, 0x08, 0x07, 0xff, 0x00, 0x00, 0x00, 0x00);  
__EEPROM_DATA(0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00);  

main()
{
  OPTION = 3;                 // FOSC/4 プリスケーラ1/16
  T1CON = 0x31;               // Timer1 settings
  TMR1IF = 0;                 // clear TMR1IF
  TMR1H = 0xf8;               // Initialize Timer1 register
  TMR1L = 0x00;
  TRISB = 0x00;               // スピーカー
  PORTB = 0;

  while(1) {
    musicPlay(Neko,3);
    musicPlay(Neko,3);    Delay500();
    musicPlay(Chime,6);   Delay500();
    musicPlay(Funeral,2); Delay500();
    musicPlay(Flog,5);    Delay500();
  }
}

byte diff[]={    // 1191
67,63,59,57,53,50,47,45,42,40,37,35,
34,31,30,28,27,25,24,22,21,20,19,17,
17,16,15,14,13,12,12,11,11,10, 9, 9,
 8, 8, 8, 7, 6, 7, 6, 5, 5, 5, 5, 5,
 4, 4, 3, 4};
void SoundPlay(unsigned tone, byte dulation)
{
   unsigned i, peri, n;
   byte j, k=0;
   byte H, L;
   unsigned term;
   unsigned all  = 1191;//0xffff-FirstPeriod+1;
   peri = FirstPeriod;
   if(tone == 255) {    // 255 は休符
      tone = 0;
      k = 1;
   }
   for(j=0; j<tone; j++) peri += diff[j];
   term = 0xffff-peri+1;
   n = 4*dulation*all/term*10;
   H = peri >> 8;
   L = peri & 0xff;
   for(i=0; i<n; ) {
     if(TMR1IF) {
       if(!k) PORTB = ~PORTB;
       TMR1H = H;               // Initialize Timer1 register
       TMR1L = L;
       TMR1IF = 0;
       i++;
    }
  }
}

void musicPlay(byte n, byte speed)
{
  byte m, i, j;
  m = eeprom_read(n);
  for(i=n+1,j=0; i<=n+m; i++) tones[j++]=eeprom_read(i);
  for(i=0; i<m; i++) SoundPlay(tones[i], speed);
}

void Delay500()               // 500m秒ディレイ
{
  int i;
  for(i=0; i<50; i++)
    __delay_ms(10); 
}

void musicPlay(byte n, byte speed)
EEPROMのnバイト目からメロディデータを読み込むことをする。先頭にバイト数があるから、そのバイト数分読み込み、それを再生する。

EEPROM音符データを用いるように変更

RobotFast.cを変更して、メロディを多く再生できるように修正します。
EEPROM音符データを用いるように変更
// ファイル名 RobotRom.c
// 外部センサオプション番号を判別してライントレースとマイク、手かざし動作を実行する。
// 明るさ設定は電源投入時直後に白レベルを読み取る。
// マイクの時間待ちに音楽を流す
// プッシュスイッチでプログラム選択可能にした。
// ランダムウォークを付け加えた
// 特別製IRセンサ高速版機能追加(LineTrace2())
// 音データをEEROMから読み込んで再生するように変更
//  LED の色
//      0:黒、1:赤、2:青、3:紫、4:緑、5:黄、6:水色、7:白

#include <htc.h>
__CONFIG(PWRTEN&HS&WDTDIS&UNPROTECT&MCLRDIS&BORDIS&IESODIS&FCMDIS);

#define _XTAL_FREQ 20000000
#define PERIOD 100
#define false 0
#define true  1
#define AN4   0x91
#define AN5   0x95
#define AN6   0x99
#define AN7   0x9d
#define AN10  0xa9
#define AN11  0xad
#define ABS(x) ((x>=0) ? (x) : -(x))
#define FirstPeriod 64345

#define SLOW  35
#define  LOW  40
#define MIDDLE 80
#define MIDDLE1 100
#define MIDDLE2 120
#define HIGH  160
#define StopState 8

#define Neko     0x00
#define Chime    0x0a
#define Funeral  0x16
#define Flog     0x3b

typedef unsigned char byte;

void LED(byte n, byte times);
void Delay50();
void Delay100();
void Delay500();
void initialize();
void setIRThreshold(byte th);
byte checkIR();
void LineTrace();
void LineTrace2();
byte getOption();
void getAD(byte channel, byte* flag);
void Mic();
void setInterrupt();
byte checkCdS();
void setThreshold(byte th);
void overHand();
void SoundPlay(unsigned tone, byte dulation);

void musicPlay(byte n, byte speed);
byte progSW();
byte setOption();
void randomWalk();

// グローバル変数の宣言
byte counter=0;
byte LeftCdS, CenterCdS, RightCdS,ExRCdS;
byte threshold[4];
byte ADch=0;
byte ConvEndFlag;
byte ADC[4]={AN4,AN5,AN11,AN6};
byte Leftspeed=208;
byte Centerspeed=208;
byte Rightspeed=208;
byte CdSInt;

byte tones[36];
__EEPROM_DATA(0x08, 0x0e, 0x0c, 0x05, 0x05, 0x11, 0xff, 0x11);
__EEPROM_DATA(0xff, 0xff, 0x0b, 0x15, 0x05, 0x13, 0x0c, 0xff);
__EEPROM_DATA(0x0c, 0x13, 0x15, 0x11, 0x11, 0xff, 0x24, 0x05);
__EEPROM_DATA(0x05, 0x05, 0xff, 0x05, 0x05, 0x05, 0xff, 0x05);
__EEPROM_DATA(0xff, 0x05, 0x05, 0x05, 0xff, 0x08, 0x08, 0x08);
__EEPROM_DATA(0xff, 0x07, 0xff, 0x07, 0x07, 0x07, 0xff, 0x05);
__EEPROM_DATA(0xff, 0x05, 0x05, 0x05, 0xff, 0x04, 0xff, 0x05);
__EEPROM_DATA(0x05, 0x05, 0x05, 0x10, 0x03, 0x05, 0x07, 0x08);
__EEPROM_DATA(0x07, 0x05, 0x03, 0xff, 0x07, 0x08, 0x0a, 0x0c);
__EEPROM_DATA(0x0a, 0x08, 0x07, 0xff, 0x00, 0x00, 0x00, 0x00);
__EEPROM_DATA(0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00);

// 割り込み処理ルーチン
void interrupt Intr(void)
{
  // 約2ms毎に割り込む
  if(T0IF) {                  // 割り込みがtimer0からか?
    counter++;
    TMR0 = PERIOD;
    T0IF = 0;                 // 割り込みフラグクリア
    return;
  }
  if(ADIF) {                  // 割り込みがADコンバーターからか?
    if(CdSInt) {              // それはCdS使用か?
      if(ADch==0) LeftCdS = ADRESH;
      else if(ADch==1) CenterCdS = ADRESH;
      else if(ADch==2) RightCdS = ADRESH;
    }
    else {  
      if(ADch==0) LeftCdS = ADRESL;
      else if(ADch==1) CenterCdS = ADRESL;
      else if(ADch==2) RightCdS = ADRESL;
      else if(ADch==3) ExRCdS = ADRESL;
    }
    ConvEndFlag=true;         // データの更新あり
    ADIF = 0;                 // 割り込みフラグクリア
  }
}

main()
{
  int st;
  byte state=0;
  
  initialize(); 
  state = setOption();        // 外部センサオプション番号を設定
  setInterrupt();             // タイマーとADの割り込み設定
  GODONE = 1;                 // AD変換スタート
  while(true) {
    switch(state) {
      case 2: LineTrace(); break; // 青 
      case 3: randomWalk();break; // 紫      
      case 4: musicPlay(Neko, 3); // 緑
              musicPlay(Neko, 3); // 緑
              state = StopState; 
                           break;
      case 5: musicPlay(Chime, 6);// 黄
              state = StopState; 
                           break;
      case 6: overHand();  break; // 水 CdSで手かざしで動かす
      case 7: Mic();       break; // 白
      case StopState: 
              PORTC &= 0x0f;      // モーター停止
              musicPlay(Funeral,2);
              break;
      case 1: LineTrace2(); break;  // 赤
      default:randomWalk();break;
    }
    st = modeSelect();            // プッシュスイッチでの状態変更
    if(st != -1) state = st;
  }
}

byte setOption()
{
  int i;
  byte state=0;
  byte extOption;                 // 外部センサオプション番号
  extOption = getOption();
  if((extOption & 0x3f)==0x38) {      // マイクモード
    state=7;
    LED(state,5);
    musicPlay(Neko, 3);               // 時間稼ぎ
    musicPlay(Neko, 3);
    CdSInt = false;
  }
  else if((extOption & 0x38)==0x20) { // 手かざしモード
    state=6;
    LED(state, 5);                    // 水色
    CdSInt = true;
    setThreshold(65);                 // 白レベルの値から閾値(65%)に決める
  }
  else if((extOption & 0x18)==0x10) { // photo refrector
    setIRThreshold(13);               // ライントレース
    state=2; 
    LED(state, 5);                    // 青
    CdSInt = false;
  }
  return state;
}  

int modeSelect()
{
  int longPush=0;
  byte st;
  Delay100(); 
  while(!RA3) {                   // まだ押されていたら
    if(counter==0) {
      if(longPush++==200) {       // 長押しだったら
        PORTC &= 0x0f;            // motor stop
        SoundPlay(52, 1);
        Delay50();
        SoundPlay(52, 1);
        LED(7,2);
        st = progSW();
        if(st != 0) return st;
      }
    }
  } 
  return -1;
}

void setInterrupt()
{ 
  // Timer0 の設定
  T0IE=1;                     // Timer0 の割り込みON
  T0IF=0;                     // 割り込みフラグクリア
  
  // ADコンバーターの設定
  ADIE = 1;                   // ADコンバータの割り込み許可
  ADIF = 0;                   // 割り込みフラグクリア
  PEIE = 1;                   // 周辺装置の割り込み許可
  GIE  = 1;                   // CPUへの割り込み許可
}
    
void initialize()
{
  PORTA = 0;                  // PORTAを0にする
  TRISA = 0;                  // PORTAを出力に設定する
  TRISB = 0x30;               // 4,5input
  PORTB = 0;
  PORTC = 0;                  // PORTCを0にする
  TRISC = 0x0f;               // PORTC下4bit入力、上4bit出力
  ANSEL = 0xF0;               // AN4,5,6,7 ON
  ANSELH = 0x0C;              // AN10,11 ON
  ADCON0 = AN4;               // ADFM=1(右詰)  AN4 adOn
                              // 1 = Right justified
  OPTION = 0;
                              // 1:8 prescale
  T1CON = 0x31;               // Timer1 settings
  TMR1IF = 0;                 // clear TMR1IF
  TMR1H = 0xf8;               // Initialize Timer1 register
  TMR1L = 0x00;

  ADC[0]=AN4;
  ADC[1]=AN5;
  ADC[2]=AN6;
  ADC[3]=AN11;
  
  CdSInt = false;             // CdSは付いていない
}

void LineTrace()
{
  while(RA3)
  { 
    switch(checkIR()){
      case 15:
      case 6: Rightspeed=Leftspeed=MIDDLE2;  // 直進   青
              RC5=0; RC7=0;
              break;
      case 14:
      case 12: Rightspeed = MIDDLE2; Leftspeed = 60; //左に行く 紫
              RC5=0; RC7=0;
              break;
      case 8: Rightspeed = MIDDLE2; Leftspeed = ~LOW;  //左に行く 赤
              RC5=0; RC7=1;
              break;
      case 7:
      case 3: Rightspeed = 60;  Leftspeed = MIDDLE2;   // 水色
              RC5=0; RC7=0;
              break;
      case 1: Rightspeed = ~LOW;  Leftspeed = MIDDLE2;    //  緑
              RC5=1; RC7=0;
              break;
    } // switch
   
    RC4 = counter < Rightspeed;
    RC6 = counter < Leftspeed;

  
  }  // while
}

void LineTrace2()
{ 
  setOption();  
  while(RA3){
    switch(checkIR()){
      
      case 6: Rightspeed=Leftspeed=240;  // 直進
              RC5=0; RC7=0;
              break;            
      case 2: Rightspeed = 140;  Leftspeed = 240;   // 右に行く
              RC5=0; RC7=0;
              break;
      case 1: Rightspeed = 50;  Leftspeed = 240;   // 右に行く
              RC5=0; RC7=0;
              break;
      case 8:
              Rightspeed = 240; Leftspeed = 50; //左に行く 
              RC5=0; RC7=0;
              break; 
      case 4: Rightspeed = 240; Leftspeed = 140; //左に行く 
              RC5=0; RC7=0;
              break;     
    } // switch
    RC4 = (counter<Rightspeed)?1:0;
    RC6 = (counter<Leftspeed)?1:0;

  }  // while
}

void LED(byte n, byte times)
{
  byte i;
  for(i=0; i<times; i++) {
    PORTA =  n;
    Delay50();                // 50msディレイ
    PORTA =  0;
    Delay50();                // 50msディレイ
  }
}

void Delay50()                // 50m秒ディレイ
{
  int i;
  for(i=0; i<5; i++)        
    __delay_ms(10); 
}

void Delay100()               // 100m秒ディレイ
{
  int i;
  for(i=0; i<10; i++)        
    __delay_ms(10); 
}

void Delay500()               // 500m秒ディレイ
{
  int i;
  for(i=0; i<50; i++)        
    __delay_ms(10); 
}

void setIRThreshold(byte th)
{
  byte i, j, x;
  int average[4]={0,0,0,0};
  GIE=0;
 // 明るいときの値 明るいと大きい値
  ADC[0]=AN4;
  ADC[1]=AN5;
  ADC[2]=AN6;
  ADC[3]=AN11;
  for(j=0; j<40; j++) {
    for(i=0; i<4; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESL;
      average[i] = (average[i]*9+x)/10;
    }
  }
  for(i=0; i<4; i++)
    threshold[i]=average[i]*th/20;
  GIE=1;
}

byte checkIR()
{
  byte status;

  if(ConvEndFlag) { // AD変換が終わったらすぐに次のチャンネルの変換を行う
    ConvEndFlag = false;
    if(++ADch==4) ADch=0;
    ADCON0 = ADC[ADch];  // 変換スタート
    GODONE = 1;
  }
  PORTA=0;
  status = 0;

  RA2 = ExRCdS<threshold[3];
  RA1 = RightCdS<threshold[2];
  RA0 = CenterCdS<threshold[1];

  status =  RA2;
  status += RA1 ? 2 : 0;
  status += RA0 ? 4 : 0;
  status += LeftCdS<threshold[0] ? 8 : 0;

  return status;
}

#define optTH 100

byte getOption()
{
  byte flag;
  byte x;

  getAD(AN4,&flag);
  getAD(AN5, &x);
  if(x) flag|=2;
  getAD(AN6, &x);
  if(x) flag|=4;
  getAD(AN7, &x);
  if(x) flag|=8;
  getAD(AN10, &x);
  if(x) flag|=0x10;
  getAD(AN11, &x);
  if(x) flag|=0x20;
  return flag;
}

void getAD(byte channel, byte* flag)
{
  int x;
  ADCON0 = channel;
  GODONE = 1;
  while(GODONE);
  x = ADRESH;
  x = x*256+ADRESL;
  *flag = x > optTH;
}


#define MICTH 4
#define MIDLOW 80
void Mic()
{
  byte i;
  int average[3]={185,185,185};
  int average2[3]={185,185,185};
  int x,y,diff[3];
  byte a,b,c,max;
  unsigned int cnt=0;
  
  GIE=0;
  ADC[0]=AN7;
  ADC[1]=AN10;
  ADC[2]=AN11;
  for(cnt=0; cnt<1000; cnt++) {
    for(i=0; i<3; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESL;
      average[i] = (average[i]*9+x)/10;
      if(x > average[i])
        average2[i] = (average2[i]*11+x)/12;
    }
  }
  // 半永久ループ
  while(RA3){  // スイッチが押されたら抜ける
    for(i=0; i<3; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESL;
      average[i] = (average[i]*9+x)/10;
      if(x > average[i])
        average2[i] = (average2[i]*11+x)/12;
      diff[i] = average2[i] - average[i];
    }
    if((diff[0] >MICTH) || (diff[1]>MICTH) || 
        (diff[2]>MICTH)) {
      a=diff[0]; b=diff[1]; c=diff[2];
      if(a>b) {
        if(a>c) { max=0; }
        else    { max=2;}
      }
      else if(b>c) { max = 1; }
      else { max=2; }

      GIE=1;
      x=500;       // 回転カウント
      switch(max){
        case 2: // Left
              PORTA = 4;
              Rightspeed = ~MIDLOW;  Leftspeed = MIDLOW;
              RC5=1; RC7=0;
              break;
        case 1: // backward
              PORTA = 2;
              if(diff[1]&1){  // たまに逆回りする
                Rightspeed = ~MIDLOW;  Leftspeed = MIDLOW;
                RC5=1; RC7=0;
              }
              else {
                Rightspeed = MIDLOW;  Leftspeed = ~MIDLOW;
                RC5=0; RC7=1;
              }
              x = 700;
              break;
        case 0: // Right
              PORTA = 1;
              Rightspeed = MIDLOW; Leftspeed = ~MIDLOW;
              RC5=0; RC7=1;
              break;
        default:
              PORTC &= 0x0f;
      }
      counter=0;
      cnt=0;
      while(cnt!=x) {
        if(counter==0) cnt++;
        RC4 = counter < Rightspeed;
        RC6 = counter < Leftspeed;
        if(!RA3) return;
      }
      PORTC &= 0x0f;
      PORTA = 0;
      GIE=0;
      Delay100();
      for(cnt=0; cnt<500; cnt++) {
        for(i=0; i<3; i++) {
          ADCON0 = ADC[i];
          GODONE = 1;
          while(GODONE);
          x = ADRESL;
          average[i] = (average[i]*9+x)/10;
        }
      } 
      for(i=0; i<3; i++) average2[i] = average[i];

    } //if
  }
  GIE=1;
}

byte checkCdS()
{
  byte status;

  if(ConvEndFlag) { // AD変換が終わったらすぐに次のチャンネルの変換を行う
    ConvEndFlag = false;
    if(++ADch==3) ADch=0;
      ADCON0 = ADC[ADch];     // ADチャンネル変更
      GODONE = 1;             // AD変換スタート
  }
    
  PORTA=0;
  RA2 = RightCdS  < threshold[2];  // 赤
  RA1 = CenterCdS < threshold[1];  // 緑
  RA0 = LeftCdS   < threshold[0];  // 青
  
  status = RA2;
  status += RA1 ? 2 : 0;
  status += RA0 ? 4 : 0;
  return status;
}

void setThreshold(byte th)    // 平均の指定%を閾値にする
{
  byte i, j, x, g;
  int average[3]={0,0,0};
  g = GIE;                    // 割り込み状態の保存
  GIE=0;                      // 割り込みは使わない
 // 明るいときの値 明るいと大きい値
  ADC[0]=AN4&0x7f;
  ADC[1]=AN5&0x7f;
  ADC[2]=AN6&0x7f;
  for(j=0; j<40; j++) {       // 平均の明るさを求める
    for(i=0; i<3; i++) {
      ADCON0 = ADC[i];
      GODONE = 1;
      while(GODONE);
      x = ADRESH;
      average[i] = (average[i]*9+x)/10;
    }
  }
  for(i=0; i<3; i++)
    threshold[i]=average[i]*th/100;
  GIE = g;                    // CPUへの割り込み状態を戻す
}

void overHand()
{
  while(RA3){
    switch(checkCdS()) {
      case 7: Rightspeed=Leftspeed=MIDDLE;    // 直進
              RC5 = RC7 = 0;
              break;
      case 6: Rightspeed = LOW;  Leftspeed = MIDDLE;
              RC5 = 0; RC7 = 0;
              break;
  
      case 4: Rightspeed = ~MIDDLE;  Leftspeed = MIDDLE;
              RC5 = 1; RC7 = 0;
              break;
      case 3: Rightspeed = MIDDLE; Leftspeed = LOW;
              RC5 = 0; RC7 = 0;
              break;
      case 1: Rightspeed = MIDDLE; Leftspeed = ~MIDDLE;
              RC5 = 0; RC7 = 1;
              break;
      case 2:
              Rightspeed=Leftspeed=~MIDDLE;
              RC5 = RC7 = 1;
              break;
      default:
      case 0: Rightspeed=Leftspeed=255;
              RC5 = RC7 = 1;
              break;
    }
    RC4 = counter<Rightspeed;
    RC6 = counter<Leftspeed;
  }  
}

byte diff[]={    // 1191
67,63,59,57,53,50,47,45,42,40,37,35,
34,31,30,28,27,25,24,22,21,20,19,17,
17,16,15,14,13,12,12,11,11,10, 9, 9,
 8, 8, 8, 7, 6, 7, 6, 5, 5, 5, 5, 5,
 4, 4, 3, 4};

void SoundPlay(unsigned tone, byte dulation)
{
   unsigned i, peri, n;
   byte j, k=0;
   byte H, L;
   unsigned term;
   unsigned all  = 1191;//0xffff-FirstPeriod+1;
   peri = FirstPeriod;
   if(tone == 255) {
      tone = 0;
      k = 1;
   }
   for(j=0; j<tone; j++) peri += diff[j];
   term = 0xffff-peri+1;
   n = 4*dulation*all/term*10;
   H = peri >> 8;
   L = peri & 0xff;
   for(i=0; i<n; ) {
     if(TMR1IF) {
       if(!k) PORTB = ~PORTB;
       TMR1H = H;               // Initialize Timer1 register
       TMR1L = L;
       TMR1IF = 0;
       i++;
    }
  }
}

void musicPlay(byte n, byte speed)
{
  byte m, i, j;
  m = eeprom_read(n);
  for(i=n+1,j=0; i<=n+m; i++) tones[j++]=eeprom_read(i);
  for(i=0; i<m; i++) SoundPlay(tones[i], speed);
}

byte progSW(){
  byte on=0;
  byte state=0;
  int t=0;
  Delay500();
  while(true){
    if(!RA3) {     // 押されたら
      Delay100() ;
      on = true;
      t=0;
    }
    if(on && RA3) {
      on = false;
      if(state++==StopState) state=0;
      //SoundPlay(52, 1);
      LED(state, 1);
      t=0;
    }
    if(counter++==0) {
      if(t++==1000) return state;    // 0も返す
    }
  }
}

void randomWalk()
{
  byte timer=0;
  while(RA3) {
    if(counter==0) {
      if(timer++==200) {
        timer = 0;
        switch(rand()&7){
          case 0: Rightspeed=Leftspeed=HIGH;  // 直進
                  RC5 = RC7 =0; break;
          case 1: Rightspeed = HIGH; Leftspeed = SLOW;
                  RC5 = RC7 =0; break;
          case 2: Rightspeed = SLOW;  Leftspeed = HIGH;
                  RC5 = RC7 =0; break;
          case 3: Rightspeed=Leftspeed=~HIGH;  // 後進
                  RC5 = RC7 = 1; break;
          case 4: Rightspeed = ~HIGH; Leftspeed = ~SLOW;
                  RC5 = RC7 = 1; break;
          case 5: Rightspeed = ~SLOW;  Leftspeed = ~HIGH;
                  RC5 = RC7 = 1; break;
          case 6: Rightspeed = HIGH; Leftspeed = LOW;
                  RC5 = RC7 = 0; break;
          case 7: Rightspeed = LOW;  Leftspeed = HIGH;
                  RC5 = RC7 = 0; break;
        }
      }
    }
    RC4 = counter < Rightspeed;
    RC6 = counter < Leftspeed;
  }
}

if(state++==StopState) state=0;
今までStopStateを有効にしていなかったので、有効にしてみる。

目次へ戻る