LoginSignup
2
1

More than 3 years have passed since last update.

H8/3664ではじめるマイコン制御・完結  ライントレースロボット

Last updated at Posted at 2019-03-18

Yellow_tracer

ライントレース_190318_0015.jpg

年末年始の暇つぶしとして触り始めたh8マイコンをどうにか実用的な形にしようと就職活動の隙間時間にライントレースロボットを作製しました.
ここまでどのような事をやってきたのかを知りたいという方がおられましたら,以下がリンクです.
H8/3664ではじめるマイコン制御0 動作環境紹介

ライントレースロボットとは黒い線上を移動するロボットのことで今回は黒ビニルテープ上を走らせます.

基板構成としましては
h8/3664f用マイコンボード
ステッピングモータ駆動用ボード
トレースセンサ用ボード
から成り立っております.

これまでのブログで要素技術についての説明は行ってあるのでここではそれらは既知として話を進めます.

ステッピングモータ駆動用ボード

ライントレース_190318_0020.jpg

ライントレース_190318_0001.jpg

モータは12V駆動のため12Vのバッテリーを用意します.
図左上のレギュレーターは12Vからマイコン駆動用の5Vを得るためのものです.

駆動は2相励磁としました.左下のコンデンサのある回路は3-stateICです.停止時の焼損を回避するため停止時Hi-Zになるようにしてあります.

励磁ですが,ICによるNOTでAに対するA-,Bに対するB-をとってあるため,一つのサーボに対して制御用の線は2本で済みます.

トレースセンサ用ボード

ライントレース_190318_0019.jpg

写真上部の3つ,左下に2つ,反射型の赤外線フォトインタラプタを用いています.
これらで白黒の判定を信号に変換しマイコンへ取り入れます.

h8/3664f用マイコンボード

はんだ付けをするのがめんどくさくなってきたので,プリント基板でパターンを描くことにしました.

アートワーク

ライントレース_190318_0014.jpg

PCBEを用いて作成しています.

紙で試し印刷をしながら調整し,
出来上がればパターンをOHPシートに印刷します.

ライントレース_190318_0003.jpg

そして感光基板に感光させます.

ライントレース_190318_0004.jpg

感光できたならば現像液に浸します.

ライントレース_190318_0008.jpg

次にエッチング液に浸し銅を溶かします.
ライントレース_190318_0010.jpg

溶かしきれたらやすり掛けを行い,ランドに穴をあけていきます.
ライントレース_190318_0012.jpg

ライントレース_190318_0013.jpg

最後にランドにはんだを付ければマイコンボードの完成です.

ライントレース_190318_0021.jpg

ライントレース_190318_0016.jpg

以上がハード部分の作製になります.
次に動作するためのプログラムを作成していきます.

Yellow_tracer.c

//割り込み関数使用可能ライントレースプログラム リモコン機能付き 完成
#include <stdio.h>
#include <H83664.H>

//関数プロトタイプ宣言----------------------------------------------------
void interrupt  moter_timerA(void);                         //タイマ割り込み関数
void interrupt  inter_232c(void);                       //232C割り込み
void interrupt  timerV(void);
// timer関数は割り込み設定でベクタ番号を19に設定しておかないと起動しない
// inter_232c関数は割り込み設定でベクタ番号を23に設定しておかないと起動しない

//マクロ------------------------------------------------------------------

//タイマ用
#define IRRTA   0x40
#define IENTA   0x40
#define CMFA    0x40

//制御用
#define OFF 0 
#define ON 1
#define ADVANCE 2
#define REVERSE 3
#define HIGH 2
#define LOW 3
#define OUT1 2
#define OUT2 5
#define STEP 150
#define POP 34
//0
//1
//2 前進
//3 後退
//速度初期値 85
//速度初期値 100がベスト
//はみ出し1段階目速度調整 85
//はみ出し2段階目速度調整 150
//旋回角度調整 大きくすればUターンできる

//グローバル変数----------------------------------------------------------

int WtimeOut;

//アナログ値読み取り変数
int i = 0, j = 0;
int AtoD_val, delay;
int volume_read();

int r_wait = 0, l_wait = 0;//moter速度変数。はみだしによってこの値を変化させる
int r_delay = 0, l_delay = 0;//加算していく。上記のwaitの値に達した地点でモーターを動かし再カウントを行う。
int out_state = 0;//はみ出しに関する変数。最後まで黒線に残っていたほうを示す。左へはみ出したら1 右へはみ出したら2となる
long tmp = 20;//moter速度調整用変数 
int out_count = OFF;//すべてはみ出すとON,すべて黒に入ればOFF

int r_rot = ADVANCE, l_rot = ADVANCE, moter_sw = ON;//回転方向、回転動作のON/OFFに関する変数
int r_sw = 1, l_sw = 1;//二層励磁用変数1~4までの値をとる。
unsigned char r_state = 0x00, l_state = 0x00, moter_sum = 0x00;//左右それぞれの二層励磁用バイト変数

//各センサ用変数
unsigned char obj_s = 0x00;//P50 0x01
unsigned char trace_s_l = 0x00;//P51 0x02
unsigned char trace_s_s = 0x00;//P52 0x04
unsigned char trace_s_r = 0x00;//P53 0x08
unsigned char r_s_l = 0x00;//P54 0x10
unsigned char r_s_r = 0x00;//P55 0x20
unsigned char remote = 0x00; //P56 0x40

int obj_sw = ON; //対物センサのON/OFF変数
int once = 1;//一度のみ動作させる条件文用変数

int degree_sw = OFF;
int degree_old_sw = ON;
int degree = 0;

unsigned char debug = 0x00;

int recv_buffer[POP];
int remote_log[POP];
unsigned int remote_count = 0;
int remote_state = 3;
int remote_sw = OFF;
int remote_old_sw = 0;
int remote_tmp = 0;
int array_count = 0;
int error_count = 0;
int error_sw = OFF;

int remote_array[7][34] = {
{1,1,0,1,0,0,1,0,1,1,1,0,1,1,0,1,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,1,1},//POWER 0
{1,1,0,1,0,0,1,0,1,1,1,0,1,1,0,1,0,0,1,1,1,0,1,0,0,0,0,0,0,1,0,1,1,1},//PLAY 1
{1,1,0,1,0,0,1,0,1,1,1,0,1,1,0,1,0,0,1,1,0,1,0,0,1,0,0,0,1,0,1,1,0,1},//CD-PAUSE 2
{1,1,0,1,0,0,1,0,1,1,1,0,1,1,0,1,0,0,1,0,0,1,1,0,0,0,0,1,1,0,0,1,1,1},//TAPE-STOP 3
{1,1,0,1,0,0,1,0,1,1,1,0,1,1,0,1,0,0,0,1,0,1,0,0,1,0,1,0,1,0,1,1,0,1},//CD-STOP 4
{1,1,0,1,0,0,1,0,1,1,1,0,1,1,0,1,0,0,0,0,1,1,1,0,1,0,1,1,0,0,0,1,0,1},//|<< 5
{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
};


int array_check1 = 0;
int array_check2 = 0;
int check_sum = 0;
int dummy_sum = 0;

int clear_sum = 0;

int recv_command=100;//初期設定は規定外の数
int remote_mode=OFF;

//メインプログラム--------------------------------------------------------
void main(void)
{
    _asm    LDC.B   #128, CCR   //全割込み禁止 CCR7bit目を1にしてマスク

    WtimeOut = OFF;

    PCR5 = 0x00;    //ポート50,51,52,53,54,55,56,57の出力設定
    PCR7 = 0x70;    //ポート74,75,76の出力設定
    PCR8 = 0xff;    //ポート80,81,82,83,84,85,86,87の出力設定

    //タイA初期化------------------------------------------------------------------------------
    TMA = 0x15;     //1秒:0x18   0.5秒間隔:0x19  0.25秒:0x1a  0.03125秒:0x1b  :Φ/128:0x15
    IENR1 |= 0x40;  //タイマA割込み許可

/*
    //タイマVの初期化--------------------------------------------------------------------------
    TCSRV = 0x00;//
    TCORA = 255;//タイムコンスタントレジスタA
    TCORB = 0;//タイムコンスタントレジスタB
    TCRV1 = 0xe3;//タイマコントロールレジスタV1
    TCRV0 = 0x4b;//125kHzを発生させる 0x4b:125khz
*/

//RS232C初期化------------------------------------------------------------------------------
//SCR3のTE,REを0にクリア。CKE1,CKE0を設定
//通信速度の設定は232Cを使用しない場合でも必要。設定していないとprintfなどの出力文字が
//正しく表示できない場合がある
    SCR3 = 0x00;
    SMR = 0x00;     //調歩同期式、データ長8ビット、パリティ無し、ストップビット長1、クロック(n=0)
    BRR = 12;       //8:57600 12:38400bps/s  25:19200  51:9600  103:4800 ターミナルの設定もこれに合わせないと文字が化ける

    SCR3 |= 0x70;   //送受信の許可、および受信割り込みの許可
//  c = SSR;
//  SSR = 0x80;

    //ウォッチドッグタイマ初期化---------------------------------------------------------------------
    TMWD = 0xff;//内部クロック 8192
    TCSRWD = 0;
    TCSRWD = 0x50;//カウンタを変更可能にする
    TCWD = 0;//カウンタ初期化
    TCSRWD = 0x54;//タイマ起動

    //配列クリア-------------------------------------------------------------------------------------
    for (i = 0; i < POP; ++i) {
        remote_log[i] = 0;
        recv_buffer[i] = 0;
    }
    _asm    LDC.B   #0, CCR //全割込み許可


    while (1) {

        if (WtimeOut == ON) {//割り込みを動かすために必要
            while (1);
        }
        TCWD = 0;//ウォッチドッグタイマ カウントクリア


        //AtoD_val = volume_read();
        //tmp = (long)AtoD_val * 389 / 1000;
        //seg(tmp);

        //各センサ値読み取り
        r_s_r = PDR5;
        r_s_l = PDR5;
        trace_s_r = PDR5;
        trace_s_s = PDR5;
        trace_s_l = PDR5;
        obj_s = PDR5;
        remote = PDR5;



        if (once == 1) {//一度きりの処理
            if ((r_s_r & 0x20) != 0x00) obj_sw = OFF;//指で押さえたとき
            else obj_sw = OFF;
            if ((r_s_l & 0x10) != 0x00) tmp = HIGH;//指で押さえたとき
            else tmp = HIGH;
            once = 0;
        }

    if(recv_command==0){
        remote_mode=ON;//リモコン操作開始
    }

    if(remote_mode==OFF){

        //センサー走行パターン----------------------------------------------------------------------------------------------------
        if ((trace_s_r & 0x08) != 0x00) l_wait = tmp + OUT1;//00001000 & 00001000 白いとき1がたつ 右はみだし左減速
        else l_wait = tmp;

        if ((trace_s_l & 0x02) != 0x00) r_wait = tmp + OUT1;//左はみだし右減速
        else r_wait = tmp;


        if ((trace_s_r & 0x08) != 0x00 && (trace_s_s & 0x04) != 0x00) l_wait = tmp + OUT2;//右大きくはみだし        
        else l_wait = tmp;

        if ((trace_s_l & 0x02) != 0x00 && (trace_s_s & 0x04) != 0x00) r_wait = tmp + OUT2;//左大きくはみだし
        else r_wait = tmp;

        if ((trace_s_r & 0x08) != 0x00 && (trace_s_s & 0x04) != 0x00 && (trace_s_l & 0x02) != 0x00) out_count = ON; //すべてはみ出し時
        else degree = 0;

        if ((trace_s_r & 0x08) == 0x00) out_state = 1;
        if ((trace_s_l & 0x02) == 0x00) out_state = 2;

        if (out_count == ON) {
            switch (out_state) {
            case 1:

                r_rot = REVERSE;
                //l_rot = ADVANCE;
                degree_sw = ON;
                break;
            case 2:
                l_rot = REVERSE;
                //r_rot = ADVANCE;
                degree_sw = ON;
                break;
            case 3:
                r_rot = ADVANCE;
                l_rot = REVERSE;
                break;
            case 4:
                r_rot = REVERSE;
                l_rot = ADVANCE;
                break;
            }
        }

        if (degree >= STEP) {
            if (degree_sw == degree_old_sw) {
                degree_old_sw = OFF;

                if (out_state == 1) {
                    out_state = 3;
                }
                if (out_state == 2) {
                    out_state = 4;
                }
            }
        }


        if ((trace_s_r & 0x08) == 0x00 && (trace_s_s & 0x04) == 0x00 && (trace_s_l & 0x02) == 0x00) {
            degree_sw = OFF;
            degree_old_sw = ON;
            degree = 0;
            out_count = OFF;
            r_rot = ADVANCE;
            l_rot = ADVANCE;
        }

        if (obj_sw == ON) {
            if ((obj_s & 0x01) == 0x00)moter_sw = OFF;//指を置くとON
            else moter_sw = ON;
        }

    }//if(remote_mode

    else{//リモコン操作コマンド

        if(recv_command==1){//PLAY
                remote_mode=OFF;
        }


            if(recv_command==2){//CD-PAUSE
                r_rot = ADVANCE;
                l_rot = ADVANCE;
            }
            if(recv_command==3){//TAPE-STOP
                r_rot = ADVANCE;
                l_rot = REVERSE;
            }
            if(recv_command==4){//CD-STOP
                r_rot = REVERSE;
                l_rot = ADVANCE;
            }
            if(recv_command==5){// |<<
                r_rot = REVERSE;
                l_rot = REVERSE;
            }
        recv_command=100;

    }

        //リモコン受信部---------------------------------------------------------------------

        if ((remote & 0x40) == 0x00) {//リモコン用信号を受信したとき
            remote_sw = ON;
            _asm    LDC.B   #128, CCR   //全割込み禁止CCR7bit目を1にしてマスク
        }
        else remote_sw = OFF;

        if (remote_sw != remote_old_sw && remote_sw == ON)remote_state = 1;//立下りエッジ
        if (remote_sw != remote_old_sw && remote_sw == OFF)remote_state = 0;//立ち上がりエッジ
        if (remote_state == 0)remote_count++;//立ち上がり時間計測

        if (remote_state == 1) {
            recv_buffer[array_count] = remote_count;
            remote_count = 0;
            array_count++;
            remote_state = 2;
        }
        remote_old_sw = remote_sw;


        //リモコンデータ走行パターン-----------------------------------------------------------------
        if (array_count == 34) {
            /*  if (array_count >= POP) {//[debug]配列の生データを出力
                    for (i = 0; i < POP; i++) {
                        printf("%d,", remote_log[i]);
                    }
                    printf("\n");
                }
            */

            //取得データを01変換-----------------------------------
            for (i = 0; i < POP; i++) {
                remote_tmp = recv_buffer[i];
                if (remote_tmp >= 30) {//H/L閾値
                    remote_tmp = 1;
                    remote_log[i] = remote_tmp;
                }
                else {
                    remote_tmp = 0;
                    remote_log[i] = remote_tmp;
                }
            }
            _asm    LDC.B   #0, CCR //全割込み許可
        //受信データのエラーチェック---------------------------
            for (i = 0; i < POP; i++) {
                if (remote_log[i] == 1)error_count++;
            }
            if (error_count > 30) {
                //printf("unmatch pattern clear array\n");
                if (array_count >= POP - 1) {
                    for (i = 0; i < POP; i++) {// 配列の初期化 
                        remote_log[i] = 0;
                    }
                    error_count = 0;
                    error_sw = ON;
                }//if (array_count >= POP-1)
            }
            else {
                error_count = 0;
                error_sw = OFF;
            }

            //受信データ識別--------------------------------------------
            if (error_sw == OFF) {
                dummy_sum = 0;
                for (array_check1 = 0; array_check1 < 7; array_check1++) {

                    for (array_check2 = 0; array_check2 < POP; array_check2++) {

                        if (remote_array[array_check1][array_check2] == remote_log[array_check2]) {
                            check_sum++;
                        }
                    }
                    if (check_sum == POP) {//受信データを配列と照合

                        //printf("%d\n",array_check1);//array_check1がそのままコマンド数字になる
                        recv_command=array_check1;//可読性向上のための移し替え
                        //printf("%d\n",recv_command);
                        check_sum = 0;
                        break;
                    }
                    else check_sum = 0;

                }//for(array_check1
            }//if(error_sw


            /* //[debug]配列のH/Lを出力
            if (array_count >= POP) {
                for (i = 0; i < POP; i++) {
                    printf("%d,", remote_log[i]);
                }
                printf("\n");
            }
            */

        }// if (array_count == 34)
        else {
            _asm    LDC.B   #0, CCR //全割込み許可
            clear_sum++;
        }

        // 配列の初期化 ---------------------------------------------
        if (clear_sum >= 5000) {
            for (i = 0; i < POP; i++) {
                recv_buffer[i] = 0;
            }
            array_count = 0;
            clear_sum = 0;
        }

    }//無限ループ
}//main

//タイマ--------------------------------------------------------------------------------------------
void interrupt timerV(void)
{

    if (TCSRV & CMFA) {
        TCSRV &= ~CMFA;
        //printf("%d",TCNTV);


       // printf("HelloWorld_V\n");

    }
    else
        TCSRV = 0;
}


void interrupt moter_timerA(void)
{
    int i;



    IRR1 &= ~0x40;  //割込み要求フラグクリア
    __break__
        //printf("HelloWorld_A\n");

        if (moter_sw == ON) {
            if (l_delay >= l_wait) {//速度調整用
                l_delay = 0;
                degree++;
                if (l_rot == ADVANCE) {
                    switch (l_sw) {
                    case 1:     //左車輪前進 二相励磁
                        l_state = 0xff;
                        l_sw = 2;
                        break;
                    case 2:
                        l_state = 0xf7;
                        l_sw = 3;
                        break;

                    case 3:
                        l_state = 0xf3;
                        l_sw = 4;
                        break;
                    case 4:
                        l_state = 0xfb;
                        l_sw = 1;
                        break;

                    }
                }
                else {
                    switch (l_sw) {
                    case 1:     //左車輪後退 二相励磁
                        l_state = 0xfb;
                        l_sw = 2;
                        break;
                    case 2:
                        l_state = 0xf3;
                        l_sw = 3;
                        break;

                    case 3:
                        l_state = 0xf7;
                        l_sw = 4;
                        break;
                    case 4:
                        l_state = 0xff;
                        l_sw = 1;
                        break;

                    }
                }
            }
            if (r_delay >= r_wait) {
                r_delay = 0;
                if (r_rot == ADVANCE) {
                    switch (r_sw) {
                    case 1:     //右車輪前進 二相励磁
                        r_state = 0xff;
                        r_sw = 2;
                        break;
                    case 2:
                        r_state = 0xfd;
                        r_sw = 3;
                        break;

                    case 3:
                        r_state = 0xfc;
                        r_sw = 4;
                        break;
                    case 4:
                        r_state = 0xfe;
                        r_sw = 1;
                        break;

                    }
                }
                else {
                    switch (r_sw) {

                    case 1:     //右車輪後退 二相励磁
                        r_state = 0xfe;
                        r_sw = 2;
                        break;
                    case 2:
                        r_state = 0xfc;
                        r_sw = 3;
                        break;

                    case 3:
                        r_state = 0xfd;
                        r_sw = 4;
                        break;
                    case 4:
                        r_state = 0xff;
                        r_sw = 1;
                        break;

                    }//switch
                }//else
            }//l_delay
            moter_sum = r_state & l_state;
            PDR8 = moter_sum;


            l_delay++;
            r_delay++;
        }//moter_sw



}

//シリアルポート入力割り込み関数
void interrupt inter_232c(void)
{

}

/*

if (TCSRV & CMFA) {

        TCSRV &= ~CMFA;

       // printf("HelloWorld_V\n");

    }
    else
        TCSRV = 0;

*/

ある程度コメントを書いたつもりですが,かなり長いのでまた別の記事で細かい説明を加えることにします.
とりあえず要点としましては,モータ駆動にはTimerA割り込みを使用,センサ入力にはポート5,モータ出力はポート8を使用しております.構造化プログラムできていないのですべてmain文,グローバル変数となっております.
よいプログラムではないのでこの部分は後々修正したいです.

動作確認

2
1
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
2
1