モータ制御評価装置による
AKI-H8(HitachiH8/3048)プログラミング
(cygwin+GCC)

Copyright(C) 3Oct2005
8Nov2004
15Oct2003


coskx

1. はじめに

1.1 この文書の構成
この文書はH8/3048のCプログラムをコンパイルする方法,AKI-H8/3048にフラッシュメモリ書き込み(転送)する方法を修得した学習者が,モータ制御評価装置(図1)で入出力装置操作プログラミングを行なうことを解説したものである。
cygwin+GCCがインストールしてある環境での使用を前提にしている。

サンプルプログラムのダウンロード

DownLoad

図1 モータ制御評価装置

1.2 AKI-H8(HitachiH8/3048)
 AKI-H8/3048(図2)は日立製作所の製品であるマイクロコンピュータH8製品群のH8/3048Fを用いて,秋月電子通商がCPUボード,マザーボードを製作販売している製品の商品名です。


マザーボード上には次の要素が搭載されています
(1)   フラッシュメモリ(ROM)書き込み回路
(2)   12V電源入力,5V出力3端子レギュレータ(12Vから安定した5Vを作るモジュール)
(3)   8ビットスイッチ
(4)   プッシュスイッチ
(5)   LED(発光ダイオード)

AKI-H8/3048でのプログラミングはパソコン上で次のように行ないます。
(1)   C言語またはアッセンブリ言語でプログラムを開発後
(2)   コンパイル・リンクを行ない実行プログラムファイルを作ります
(3)   ロードモジュールに変換します
(4)   RS232C通信でロードモジュールをH8に送信(フラッシュメモリに書き込む)
(5)   実行


H8-MB.JPG

図2 AKI-H8 マザーボード

1.3 モータ制御評価装置

モータ制御評価装置では,マザーボードを拡張し,図3のように入出力装置を使用できるようになっている。

図3 モータ制御評価装置の各部紹介

2.CPUから接続された入出力装置とIOポート割り当て

入出力装置の回路図とポート割り当てを図4と表1に示します。



図4 モータ制御評価装置の各部の回路

図で「P4-2」というのは「ポート4の第2ビット(Port4 Bit2)」の意味であり,
「CN1-33」というのは「コネクタ1の33番ピン」という意味である。
コネクタは1から4まであり,コネクタには複数のピンが2列で並んでいる。

 

表1 ポート・ビットの割り当て
ポート・ビット 用途 入出力

Port2 Bit0

8bitDIPスイッチ 入力

Port2 Bit1

8bitDIPスイッチ 入力

Port2 Bit2

8bitDIPスイッチ 入力

Port2 Bit3

8bitDIPスイッチ 入力

Port2 Bit4

8bitDIPスイッチ 入力

Port2 Bit5

8bitDIPスイッチ 入力

Port2 Bit6

8bitDIPスイッチ 入力

Port2 Bit7

8bitDIPスイッチ 入力

Port4 Bit0

モータ回転方向制御 出力

Port4 Bit1

モータ回転方向制御 出力

Port4 Bit2

リミットスイッチ 入力

Port4 Bit4

プッシュスイッチ 入力

Port4 Bit5

プッシュスイッチ 入力

Port4 Bit6

プッシュスイッチ 入力

Port4 Bit7

プッシュスイッチ 入力

Port5 Bit0

LED 出力

Port5 Bit1

LED 出力

Port5 Bit2

電球 出力

 

3.サンプルプログラムのダウンロード

ここからサンプルプログラムをダウンロードできます。

DownLoad

 

4.サンプルプログラム

このサンプルプログラムはコンパイラシステムが供給している「3048f.h」と小坂研究室で開発した「h8_3048.h」を利用することを前提としている。

4.1 シリアル通信

プログラム書き込み用通信回線はそのままプログラム実行時にも使えます。
実行時にはハイパーターミナルを起動しておいて下さい。
実行時にはハイパーターミナルを起動しておいて下さい。
サンプルフォルダ中の次に示すアイコンで起動すると,設定済みのハイパーターミナルが起動します。

Async, 8bit, NoParity, stop1, 38400baud, (Backspace:Ctrl+H, Space, Ctrl+H)で設定されています。

ハイパーターミナルを利用した,ビットスイッチやプッシュスイッチのチェックおよびキーボードとの通信プログラムです。
ビットスイッチやプッシュスイッチのチェックの時はそれぞれのスイッチを動かしてみてください。


パソコン画面への出力(WindowsのHyperTerminal使用)
パソコン(キーボード)からの入力(WindowsのHyperTerminal使用)

リスト 1.1
なにかのキーが押されると「Hello world!」を表示する。
通信作業の時は必ず,関数initSCI1()を呼び出して,SCI1の初期化が必要である。
while(1)というのは無限ループの記述方法

●SCIというのはシリアルコミュニケーションインタフェイスNo1のことで,H8/3048に
内蔵されている通信機能のことである。この機能を用いている関数には「SCI1」がつ
いている。

/****************************************
シリアル通信インタフェイス(SCI) (TXD,RXD)
「Hello world!」を表示

◎getCharSCI1()
呼び出されるとSCIからデータが来るまで(ホストのターミナルソフト(例え
ばハイパーターミナル)でどれかのキーが押されるまで)待ち,文字コードを持
ち帰る。
****************************************/

#include "3048f.h"
#include "h8_3048.h"

main()
{
    int ch;
    initSCI1();/*SCI1初期化*/
    SCI1_printf("       ** Serial Communication Interface **\n");
    while (1) {
        SCI1_printf("Key in any key.\n");
        ch=getCharSCI1();
        SCI1_printf("           Hello world! \n");
    }
}
実行例(ハイパーターミナル画面)
       ** Serial Communication Interface **
Key in any key.
a           Hello world!
Key in any key.
b           Hello world!
Key in any key.
c           Hello world!
Key in any key.

 ●画面への表示をそのままファイル化する方法

リスト 1.2
2数の和と差の計算

/****************************************
シリアル通信インタフェイス(SCI) (TXD,RXD)
2つの数の和と差を求める

myint=getIntSCI1("honya honya=>");
SCI(ホストPCのターミナルソフト(例えばハイパーターミナル))に
「hony honya=>」と出力した後,SCI(ホストPCのキーボード)からの
整数値入力待ちになる。
整数が入力されたらmyintに値を格納する
****************************************/

#include "3048f.h"
#include "h8_3048.h"

main()
{
    int x,y,add,diff;
    initSCI1();/*SCI1初期化*/
    SCI1_printf("       ** Serial Communication Interface **\n");
    while (1) {/*無限ループ*/
        x=getIntSCI1("Key in an integer number x=>");
        y=getIntSCI1("Key in an integer number y=>");
        add=x+y;
        diff=x-y;
        SCI1_printf("x=%d y=%d x+y=%d\n",x,y,add);
        SCI1_printf("x=%d y=%d x-y=%d\n",x,y,diff);
    }
}
実行例(ハイパーターミナル画面)
       ** Serial Communication Interface **
Key in an integer number x=>26
Key in an integer number y=>31
x=26 y=31 x+y=57
x=26 y=31 x-y=-5
Key in an integer number x=>100
Key in an integer number y=>-20
x=100 y=-20 x+y=80
x=100 y=-20 x-y=120
Key in an integer number x=>

 ●画面への表示をそのままファイル化する方法

リスト 1.3
スペースキーが押されると「SCI1_printf」のデモを行なう。
どのような動作になるか,プログラムを読みながら,確認してください。

/****************************************
シリアル通信インタフェイス(SCI) (TXD,RXD)
(1)SCI整数値入力を促し,入力されたら,その値をそのままSCIへ返す
(2)getCharSCI1()とchkgetCharSCI1()の違いをプログラム上で確認する

1)getCharSCI1()
呼び出されるとSCIから(ホストPCのターミナルソフト(例えばハイパー
ターミナル)から)文字データをもらって帰ってくる。ただし,ホストPCの
キーが押されていない場合は,押されるまで待ち,キーが押されたら,押され
たキーの文字コードを持って帰ってくる。

2)chkgetCharSCI1()
呼び出されるとSCIから(ホストPCのターミナルソフト(例えばハイパー
ターミナル)から)文字データをもらって帰ってくる。ただし,ホストPCの
キーが押されていない場合は,押されるまで待つ様なことはせずに,すぐに呼
び出したところに帰る。キーが押されていたらそのキーの文字コードを持ち帰
り,押されていかったらた負の値を持って帰ってくる。
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

main()
{
    int num;
    initSCI1();/*SCI1初期化*/
    SCI1_printf("       ** Serial Communication Interface **\n");
    while (1) {
        do {
            num=getIntSCI1("Key in a positive integer (999 then next)=>");
            SCI1_printf("Your number is %d %x\n",num,num);
        } while (num!=999);
        SCI1_printf("Key in [SPACE key] then start or stop \n");
        while (getCharSCI1()!=' ') {
            putCharSCI1('A');
        }
        while (chkgetCharSCI1()!=' ') {
            msecwait(100);
            putCharSCI1('B');
        }
        SCI1_printf("\nKey in [SPACE key] then start or stop \n");
        while (getCharSCI1()!=' ');
        num=0;
        while (chkgetCharSCI1()!=' ') {
            msecwait(100);
            SCI1_printf(" %d",num++);
        }
        SCI1_printf("\n");
    }
}

 ●画面への表示をそのままファイル化する方法

練習問題1A 次の作業を行いなさい。

(1)リスト1.1を参考に,次のプログラムを作りなさい。
キーボードから「x」のキーを1回押すと文字Aが1つ表示され,もう一度「x」のキーを1回押す
と文字Bが1つ表示され,再び「x」のキーを1回押すと文字Aが1つ表示され,・・・のように「x」
のキーを1回押すごとに,文字Aと文字Bが交互に表示され,電源を切るまで無限に繰り返す

(2)リスト1.2を参考に,2つの整数値をキーボードから受け取り,積を表示するプログラムを作
りなさい。ただし,この作業は無限に行うことができるようにする。

(3)リスト1.3を参考に通信を用いて次のプログラムを作りなさい。
CPU起動後,キーボードから「y」のキーが押されるまで,文字Aを連続して表示し続け,押され
ると今度は文字Bを連続して表示し続け,再度「y」のキー押されると再び文字Aを表示し続ける。
このような動作が交互に行われ,電源を切るまで無限に繰り返す。

(4)アドレス0x0000から0x03FFまでのメモリを十六進ダンプするプログラムを作りなさい。
ヒント int型変数ptrに0x1200が入っている時,アドレス0x1200の内容を表示するには
次のように書くと良い。
SCI1_printf(" %02x",*(unsigned char *)ptr);
実行例
memory dump 0x0000-0x03ff
     +0 +1 +2 +3 +4 +5 +6 +7 +8 +9 +A +B +C +D +E +F
0000 00 00 01 00 ff ff ff ff ff ff ff ff ff ff ff ff
0010 ff ff ff ff ff ff ff ff ff ff ff ff ff ff ff ff



(5)ここでのプログラミングでは,PCのキーボードのキー操作が,シリアル通信でマイコン
H8/3048に送信され,マイコンがシリアル送信した文字列を,PCの画面に表示していた。
ところで,通信には時間がかかっていることを実感しよう。
通信速度38400baudというのは38400bit/secの通信速度であり,,1byte送信するのに10bit
が送信される。(スタートビットとストップビットが追加されるため)
すなわち,3840byte/secの通信速度ということになる。1文字送信する作業は,マイコン
にとって,他の作業に比べて遅い作業である。(PCが受信した文字を画面に表示する作業は
高速なので,通信が主となるプログラムの実行時間は,その大半が通信時間である。)
3840byte(半角文字で3840文字)を送信するループを10回ループさせると,全部で何秒か
かることが予想されるか。またこの作業を実際に行なうプログラムをつくり,時計を見ながら
確かめなさい。

(6)「RS232C」をキーワードとして,シリアル通信について調べて,まとめなさい。

(7)ファイルh8-01.hを見ると,最初のところにh8-01.hで公開している関数の説明がある。
SCI ch1(シリアルコミュニケーションインタフェイス チャンネル1)関係のすべての関数につ
いてその機能を調べ,動作について説明しなさい。

練習問題1B 次の作業を行ないなさい。

(1)指定したアドレスから0x100byteをメモリダンプするプログラムを作りなさい。ただし指定アドレスは十六進の1の位は0とする。

実行例
start address (0xnnnn) =0x400
memory dump 0400-04ff
     +0 +1 +2 +3 +4 +5 +6 +7 +8 +9 +A +B +C +D +E +F
0400 18 88 6e f8 00 32 7a 06 00 00 00 50 0a f6 0b 96
0410 73 0e 47 0e 7a 00 00 00 00 50 0a f0 0b 90 0b 70
:

(2)指定したアドレスから0x100byteをメモリダンプするプログラムを作りなさい。ただし指定アドレスは十六進の下位2桁は0とし,
この2桁は入力時に省略されることとする。「(2)」での表示アドレスは0x0000-0xFFFFしかないが,ここではH8/3048のモード7
の範囲である0x00000-0xFFFFFを表示するものとする。
例えば0x21が入力された場合は0x2100-0x21FFを表示し,0xFEFが入力された場合は0xFEF00-0xFEFFFを表示する。

実行例
start address (0xnnn) =0xFEF
memory dump FEF00-FEFff
      +0 +1 +2 +3 +4 +5 +6 +7 +8 +9 +A +B +C +D +E +F
FEF00 FF FF FF FF FF FF FF FF FF FF FF FF FF FF FF FF
FEF10 00 00 00 00 50 0a f0 0b 73 0e 47 0e 7a 90 0b 70
:


(3)現在の通信速度は38400bit/secに設定されているが,9600bit/secあるいは19200bit/secに設定するにはどのようにしたらよいか
関数initSCI1()を作り直しなさい。ハードウェアマニュアルのSCIの項目を参考にしなさい。 


4.2 LED駆動

リスト 2.1
無駄ループによるウエイト関数を用いたLEDの点滅駆動
LEDを操作する時には,LED関係の初期化関数initLed()を1回だけ最初に呼び出さなければならない。

/****************************************
LED×2(秋月マザーボード付属) (P5-0,P5-1) *1
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

main()
{
    unsigned int count=0;
    initSCI1(); /*SCIch1の初期化 シリアル通信をする場合は必要*/
    initLed();  /*LEDの制御のための初期化 LEDを制御する場合は必要*/
    SCI1_printf("       **     LED(P5-0,P5-1) winking     **\n");
    while (1) {
        SCI1_printf("count=%5u \n",count++);
        turnOnLed(0);  /*LED0のON*/
        turnOffLed(1); /*LED1のOFF*/
        msecwait(500);
        turnOnLed(1);  /*LED1のON*/
        turnOffLed(0); /*LED0のOFF*/
        msecwait(500);
    }
}

図5のLEDが対象となるLEDです。

H8-LED.JPG


H8-LEDD.JPG - 9,332BYTES

図5 2つのLED

リスト 2.2

無駄ループによるウエイト関数を用いたLEDの点滅駆動

プログラム中に2msec点灯し,6msec消灯するようなループがある。
このようなLEDの制御を行なっても,人間の目には点滅は見えないで,LEDが暗く点灯しているように見える。
この制御方法はパルス幅変調(Pulse Width Moduration, PWM)と呼ばれている。
この例では点滅周期が8msecなので,PWM周期が8msecである。
また,PWM周期8msec中,点灯時間は2msecなので,2/8→25%の点灯率である。
この状態のことはデューティ比25%と呼ばれている。
別のループでは4msec点灯4msec消灯なのでPWM周期は8msec,デューティ比50%である。

/****************************************
LED×2(秋月マザーボード付属) (P5-0,P5-1) *1
PWM(Pulse Width Modulation パルス幅変調)によるLEDの光度制御
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

main()
{
    int i;
    unsigned int count=0;
    initSCI1();
    initLed();
    SCI1_printf("       **     LED(P5-0,P5-1) winking     **\n");
    while (1) {
        count=0;
        SCI1_printf("count=%5u \n",count++);
        for (i=0;i<125;i++) {
            turnOnLed(0);  /*LED0のON*/
            turnOnLed(1);  /*LED1のON*/
            msecwait(0);
            turnOffLed(0); /*LED0のOFF*/
            turnOffLed(1); /*LED1のOFF*/
            msecwait(8);
        }
        SCI1_printf("count=%5u \n",count++);
        for (i=0;i<100;i++) {
            turnOnLed(0);  /*LED0のON*/
            turnOnLed(1);  /*LED1のON*/
            msecwait(1);
            turnOffLed(0); /*LED0のOFF*/
            turnOffLed(1); /*LED1のOFF*/
            msecwait(7);
        }
        SCI1_printf("count=%5u \n",count++);
        for (i=0;i<100;i++) {
            turnOnLed(0);  /*LED0のON*/
            turnOnLed(1);  /*LED1のON*/
            msecwait(2);
            turnOffLed(0); /*LED0のOFF*/
            turnOffLed(1); /*LED1のOFF*/
            msecwait(6);
        }
        SCI1_printf("count=%5u \n",count++);
        for (i=0;i<100;i++) {
            turnOnLed(0);  /*LED0のON*/
            turnOnLed(1);  /*LED1のON*/
            msecwait(4);
            turnOffLed(0); /*LED0のOFF*/
            turnOffLed(1); /*LED1のOFF*/
            msecwait(4);
        }
        SCI1_printf("count=%5u \n",count++);
        for (i=0;i<100;i++) {
            turnOnLed(0);  /*LED0のON*/
            turnOnLed(1);  /*LED1のON*/
            msecwait(8);
            turnOffLed(0); /*LED0のOFF*/
            turnOffLed(1); /*LED1のOFF*/
            msecwait(0);
        }
    }
}

練習問題2A 次のプログラムを作りなさい。

(1)リスト2.1を参考に,1秒周期で両方のLEDが同時に点滅するプログラム
(2)0.5秒周期で左右のLEDが交互に点滅するプログラム
(3)0.5秒ごとに2つのLEDが次のような4つの点滅パターンを繰り返すプログラム
   (○は消灯,●は点灯を示す)
   ○○,○●,●○,●●
(4)0.5秒ごとに「LED0を2回点滅の後LED1を2回点滅」を繰り返すプログラム
(5)0.5秒ごとに点灯状態が変化し,次の点滅パターンを繰り返すプログラム
   左側2回点滅→右側2回点滅→左側1回点滅→右側1回点滅
(6)10秒周期で両方のLEDが同時に点滅するプログラムをつくり動作させなさい。
  動作中にアナログテスタを使って,CN3の31,32の電圧を測定しなさい。
(7)リスト2.2において,大きなループを1周する時間について検討する次の2つの作業を
  行いなさい。
  A) リスト2.2を実際に動作させて,時計で測定しなさい。必要なら数回ループさせて
    平均を求めなさい。
  B) リスト2.2において,SCI通信部と関数msecwait()の作業時間が卓越し,他の
    作業にかかる時間を無視して,1ループにかかる時間を計算しなさい。
    報告書では計算方法がわかるようにしなさい。
(8)ファイルh8-01.hの最初の説明を読んでLED関係の関数の機能をまとめて説明しなさい。

練習問題2B 次の作業を行ないなさい。

(1)h8-01.h中にある関数initLed(),turnOnLed(),turnOffLed()について説明しなさい。
  なおH8/3048ハードウェアマニュアルの関連する説明を抜き出しなさい。(9.6 ポート5,モード7参照)
(2)次のような設計仕様の場合のLED初期化関数initLed4()とturnOnLed(),turnOffLed()を作りなさい。
  ポート5のbit0,bit1,bit2,bit3に制限抵抗付きのLEDが接続されているとします。
  void initLed4(void) LED初期化関数
  void turnOnLed(int number) LEDを点灯させる関数。
    ただし,引数は0,1,2,3を取り,LED0,1,2,3をそれぞれ個別に点灯させます。
  void turnOffLed(int number) LEDを消灯させる関数。
    ただし,引数は0,1,2,3を取り,LED0,1,2,3をそれぞれ個別に消灯させます。
(3)「(2)」で作成した関数を使って,ポート5のbit0,bit1,bit2,bit3にLEDがついていると仮定して,
  10秒周期で4つのLEDが同時に点滅するプログラムをつくり動作させなさい。
  動作中にアナログテスタを使って,このプログラムが4つのビットを駆動していることを検証しなさい。
  (ヒントCN3のどこか)

4.3    タイマ割り込みLED点滅プログラム

リスト 3.1

通常の関数は,関数がプログラム中の他の関数から呼び出されたときに作業を行ないます。これに対して,割り込み関数は何らかの割り込み要因によって呼び出される関数です。
タイマ割り込み関数は,タイマ割り込み初期設定によって設定された時間間隔で起動する割り込み関数です。このプログラムでは,500msのタイマ割り込み初期設定が行なわれ,CPUの割り込み許可がなされ,タイマがスタートした後,プログラムの流れは
while(1);
となり,何もしない無限ループに突入します。しかし,500ms(0.5秒)ごとにタイマ割り込み関数「interrupt_cfunc()」が起動し,LEDのON−OFFが継続して行なわれます。変数tickはstatic修飾されているので,関数が呼び出されたときに,前回呼び出しの時の値が残っています。0が代入されるのははじめの1回だけです。tick=1-tickの演算により,tickの値は0,1を繰り返します。
ロボットの制御には一定時間ごとに起動する定時間割り込み(タイマー割り込み)が良く用いられます。またPWMの生成にもこの定時間割り込みが用いられる場合があります。

タイマ割り込みを用いたLEDの点滅駆動
最適化コンパイルされた実行モジュールにおいては,volatile修飾子がないグローバル変数を割り込み関数と通常関数で共有すると動作が異常になることがある。最適化コンパイルされた実行モジュールではメモリ上の変数を一度レジスタに読み込むとその値をそのまま使い続けることがある。割り込み関数によってその変数の値が変化していることに気づくことが出来ない。volatile修飾子をつけると,その変数の値を使う時には必ずメモリから再読み込みする実行モジュールが出来る。「volatile」とは「変化しやすい」の意味。

/****************************************
タイマ割り込み (ITU0,ITU1)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

unsigned int counter=0;
volatile unsigned int vcounter=0;

main()
{
    initSCI1();
    initLed();
    initTimer01Int(500); /*時間割り込み500msec ch0,ch1使用*/
    SCI1_printf("       **   Timer Interrupt test with LEDs    **\n");
    E_INT();             /*CPU割り込み許可*/
    startTimer01();      /*時間割り込みタイマスタートch0,ch1*/
    while (1) {
        SCI1_printf("counter=%d vcounter=%d\n",counter,vcounter);
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int tick=0;
    if (tick==1) {
        turnOnLed(0);  turnOffLed(1);
        counter++;
        vcounter++;
    } else {
        turnOffLed(0);  turnOnLed(1);
    }
    tick=1-tick;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

 ●修飾子「volatile」について
英語の意味は「変化しやすい」の意味である。
割り込み関数と,通常の(mainを含む)関数の間で共有する変数につける。
    初級・中級向け(初心者は読み飛ばしてよい)説明
本当のことをいうと,コンパイラに対する指示である。コンパイラは機械語コードを最適化する。
グローバル変数はメモリ上に置かれるが,最適化された機械語コードでは,その変数の値が変更されない限り
メモリからCPUのレジスタに読み込まれた値を保持していて,アクセスごとに毎回メモリを読みに行くわけではない。
そのため,その変数を割り込み関数が変更した(割り込み関数は値を変更しているので,メモリを書き換える)とし
ても,気づかずに,レジスタに読み込まれた値を使い続けてしまう。
「volatile」は,このような最適化をしてはいけないという意味で,その変数の値を使う時は,毎回メモリ上の値を使
いなさいという意味になる

リスト 3.2
タイマ割り込みを用いたLEDの点滅駆動 タイマ割り込みのON-OFF
スペースキーを押すと動作のスタートストップが出来る。

/****************************************
タイマ割り込み (ITU0,ITU1)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

main()
{
    unsigned int count=0;
    initSCI1();
    initLed();
    initTimer01Int(500); /*時間割り込み500msec ch0,ch1使用*/
    SCI1_printf("       **   Timer Interrupt test with LEDs    **\n");
    SCI1_printf("Key in [SPACE key] then start or stop \n");
    while (1) {
        while (getCharSCI1()!=' ');
        E_INT();             /*CPU割り込み許可*/
        startTimer01();      /*時間割り込みタイマスタートch0,ch1*/
        while (chkgetCharSCI1()!=' ') SCI1_printf("count=%5u    \r",count++);
        stopTimer01();      /*時間割り込みタイマストップch0,ch1*/
        D_INT();             /*CPU割り込み禁止*/
        turnOffLed(0);
        turnOffLed(1);
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int tick=0;
    if (tick==1) {
        turnOnLed(0);  turnOffLed(1);
    } else {
        turnOffLed(0);  turnOnLed(1);
    }
    tick=1-tick;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

リスト 3.3
タイマ割り込みを用いたLEDの点滅駆動 タイマ割り込みの間引き動作

/****************************************
タイマ割り込み (ITU0,ITU1)
割り込み周期は10msecだが,500msに1回しか働かない割り込み関数
****************************************/

#include "3048f.h"
#include "h8_3048.h"

main()
{
    unsigned int count=0;
    initSCI1();
    initLed();
    initTimer1Int(10000); /*時間割り込み10000μsec ch1使用*/
    SCI1_printf("       **   Timer Interrupt test with LEDs    **\n");
    SCI1_printf("Key in [SPACE key] then start or stop \n");
    while (1) {
        while (getCharSCI1()!=' ');
        E_INT();             /*CPU割り込み許可*/
        startTimer1();      /*時間割り込みタイマスタート ch1*/
        while (chkgetCharSCI1()!=' ') SCI1_printf("count=%5u    \r",count++);
        stopTimer1();      /*時間割り込みタイマストップ ch1*/
        D_INT();             /*CPU割り込み禁止*/
        turnOffLed(0);
        turnOffLed(1);
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int count=0;
    static int tick=0;
    if (count==0) {
        if (tick==1) {
            turnOnLed(0);  turnOffLed(1);
        } else {
            turnOffLed(0);  turnOnLed(1);
        }
        tick=1-tick;
    }
    count++;
    if (count==50) count=0;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

リスト 3.4
タイマ割り込みを用いたLEDの光度制御駆動 

/****************************************
タイマ割り込み (ITU0,ITU1)
割り込み周期1msecの割り込み関数
PWM駆動によるLEDの光度制御
****************************************/

#include "3048f.h"
#include "h8_3048.h"

volatile unsigned int sec=0;
volatile int pwmValue=0;
const int pwmIndex[]={0,1,2,4,8}; /*ROM領域に配置される*/

main()
{
    initSCI1();
    initLed();
    SCI1_printf("       **   Timer Interrupt test with LEDs    **\n");
    initTimer1Int(1000); /*時間割り込み1000μsec ch1使用*/
    E_INT();             /*CPU割り込み許可*/
    startTimer1();      /*時間割り込みタイマスタート ch1*/
    while (1) {
        pwmValue=pwmIndex[sec%5];
        SCI1_printf("pwmValue= %d/8 \n",pwmValue);
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int count=0;
    static int tick=0;
    if (tick<pwmValue) {
        turnOnLed(0);   turnOnLed(1);
    } else {
        turnOffLed(0);  turnOffLed(1);
    }
    tick++;
    if (tick==8) tick=0;
    count++;
    if (count==1000) {
        count=0;
        sec++;
    }
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

リスト 3.5
タイマ割り込みを用いた電源ONからの時間の測定

/****************************************
タイマ割り込み (ITU0,ITU1)
タイマ割り込みを用いた電源ONからの時間の測定
電源がONになった時からどれだけ時間が経過した
かをホストPCのターミナルに表示する
時間は0.1秒(100msec)精度で表示する
****************************************/

#include "3048f.h"
#include "h8_3048.h"

volatile unsigned int decisec=0;
volatile int request=0;

main()
{
    int localtime,min,sec,dsec;
    initSCI1();
    initLed();
    SCI1_printf("       **   Running Time     **\n");
    initTimer01Int(100); /*時間割り込み100msec ch0ch1同時使用*/
    E_INT();             /*CPU割り込み許可*/
    startTimer01();      /*時間割り込みタイマスタート ch0,ch1*/
    while (1) {
        if (request) {
            localtime=decisec;
            min=localtime/600;
            sec=localtime/10%60;
            dsec=localtime%10;
            SCI1_printf("%3d.%02d.%d \r",min,sec,dsec);
            request=0;
        }
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    decisec++;
    request=1;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

実行の様子
       **   Running Time     **
  4.17.7

練習問題3 次のプログラムを作りなさい。

(1)リスト3.1において割り込み周期が1秒になるように改造しなさい。
(2)リスト3.3を参考にinitTimer1Int()を用いて3秒周期のLED点滅を行なう。(引数がマイクロ秒であること,引数にはshort int型が用いられていることに注意)
(3)リスト3.2,3.5を参考に100msecごとの割り込みを用いて,ストップウォッチを作成せよ。スタート・ストップはキーボードのキーに割り当てると良い。また割り込み関数内で表示を行なってはいけない。スタート:Aキー,ストップ:Bキー,クリア:Cキーを割り当てる。
(4)リスト3.4を参考にキーボードから0から10までの整数をint型変数ratioに受け取り,「3.4」のプログラムで,点灯時間をratio/10のデューティ比になるようにしなさい。またデューティ比の変更は何回でもできるようにしなさい。
(5)ここまでで取り上げたタイマ割り込みの割り込み関数は作業量も少なく,全体の動作に関して何も影響を与えないで,うまく動作している。
1msecの割り込み周期でプログラミングしたら,割り込み関数の作業時間はどこまで長くできるか。また,割り込み周期以上に長い作業時間を割り込み関数が行ったとしたらなにが起こると予想されるか。
(6)1msecの割り込み周期でプログラミングしている。もし38400baudのシリアル通信(3840byte/sec)が設定されているとして,割り込み関数内でSCI1printf()などの関数で文字列を送信するとしたら,半角文字で何文字までなら理論上可能と考えられるか。送信作業以外の作業時間は無視できるものとする。
(7)ファイルh8-01.hの最初の説明を読んでタイマ割り込み(タイミング割り込み)関係の関数の機能をまとめて説明しなさい。



 

4.4    8ビットDIPスイッチプログラム

リスト 4.1
8ビットDIPスイッチプログラム

/****************************************
8ビットDIPスイッチ(秋月マザーボード付属)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

const char status[][5]={"OFF","ON "};

main()
{
    int i;
    initSCI1();
    init8BitSW();
    SCI1_printf("       **        8-bit DIP Switch        **\n");
    while (1) {
        SCI1_printf("%08b %02x =",get8BitSW(),get8BitSW());
        for (i=0;i<8;i++) {
            SCI1_printf("%s ",status[check8BitSW(i)]);
        }
        SCI1_printf("\n");
    }
}

H8-8BITSW.JPG - 46,974BYTES
H8-8BITSWD.JPG - 12,938BYTES

図6 8ビットDIPスイッチ

練習問題4A 次のプログラムを作りなさい。

(1)8bitSWの1がOFFの時,0.5秒周期で2つのLEDを同時点滅,8bitSWの1がONの時,1秒周期で2つのLEDを同時点滅するプログラム。
(2)8bitSWのすべてのビットがOFFの時,0.5秒周期で2つのLEDを同時点滅,8bitSWの1がONの時,1秒周期で2つのLEDを同時点滅,8bitSWの2がONの時,2秒周期で2つのLEDを同時点滅,8bitSWの1・2が同時ONの時にはLEDは消灯するプログラム。
(3)ファイルh8-01.hの最初の説明を読んで8bitSW関係の関数の機能をまとめて説明しなさい。

練習問題4B

(1)8bitスイッチの回路図を見ると,CPUの端子からスイッチを経てGNDに接続されているだけである。
通常はこの回路ではスイッチの状態を読み取ることができない。
スイッチを読み取るプログラムの初期化部分の意味(8bitSWのプルアップ設定)とあわせてどうして可能なのか検討し,説明しなさい。
なおH8/3048ハードウェアマニュアルの関連する説明を抜き出しなさい。(9.3 ポート2参照)
また小坂のweb文書「h8CPU_Input.html」も参考にしなさい。
(2)8bitスイッチで,4つのスイッチをON,残りの4つのスイッチをOFFにしなさい。
8bitスイッチの初期化をともなうプログラム(例えば「eightswh.c」)を動作させ,アナログテスタを使って,
8ビットスイッチのON-OFFの状態が電圧として見えていることを検証しなさい。(ヒントCN3のどこか)
「H8-MB-Pro.html」の「参考1 H8ピン配置」を参照しなさい。
どのように検証したか(テスタの赤黒を何処に触れたのかを含む),どのような結果が得られたか報告しなさい。
(3)次のポートのビットがCN1,CN2,CN3のどこのピンに見えるのかを答えなさい。
「H8-MB-Pro.html」の「参考1 H8ピン配置」を参照しなさい。
1)ポート5のbit0からbit3
2)ポート2のbit0からbit7
3)ポート1のbit0からbit7
3)ポート3のbit0からbit7
3)ポートAのbit0からbit7
3)ポートBのbit0からbit7

 

4.5    プッシュスイッチプログラム

リスト 5.1
プッシュスイッチプログラム

/****************************************
プッシュスイッチ×4(秋月マザーボード付属) (P4-4..P4-7)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

const char status[][5]={"OFF","ON "};

main()
{
    int i;
    initSCI1();
    initPushSW();
    SCI1_printf("       **          Push Switch           **\n");
    while (1) {
        for (i=0;i<4;i++) {
            SCI1_printf("bit%d:%s ",i,status[checkPushSW(i)]);
        }
        SCI1_printf("\n");
    }
}

リスト 5.2
プッシュスイッチ指令でPWM駆動によるLEDの光度制御

/****************************************
プッシュスイッチ×4(秋月マザーボード付属) (P4-4..P4-7)
割り込み周期1msecの割り込み関数
PWM駆動によるLEDの光度制御
****************************************/

#include "3048f.h"
#include "h8_3048.h"

volatile int pwmValue=0;
const int pwmIndex[]={1,2,4,8};

main()
{
    int i,value;
    initSCI1();
    initPushSW();
    initLed();
    initTimer1Int(1000); /*時間割り込み1000μsec ch1使用*/
    E_INT();             /*CPU割り込み許可*/
    startTimer1();      /*時間割り込みタイマスタート ch1*/
    SCI1_printf("       **    LED PWM Drive with Push Switch     **\n");
    while (1) {
        value=0;
        for (i=0;i<4;i++) {
            if (checkPushSW(i)) value=pwmIndex[i];
        }
        pwmValue=value;
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int tick=0;
    if (tick<pwmValue) {
        turnOnLed(0);   turnOnLed(1);
    } else {
        turnOffLed(0);  turnOffLed(1);
    }
    tick++;
    if (tick==8) tick=0;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

H8-PUSHSW.JPG - 31,142BYTES
H8-PUSHSWD.JPG - 14,425BYTES

図7 プッシュスイッチ

練習問題5 次のプログラムを作りなさい。

(1)すべてのプッシュスイッチがOFFの時,0.5秒周期で2つのLEDを同時点滅,プッシュスイッチの1がONの時,1秒周期で2つのLEDを交互点滅,プッシュスイッチの2がONの時,2秒周期で2つのLEDを交互点滅。それ以外の状況ではLED消灯するプログラム。
(2)プッシュスイッチの状態によって2つのLEDの同時PWM駆動を行なう。すべてのプッシュスイッチがOFFの時,なにもしない。プッシュスイッチの1がONの時,デューティー比100%で点灯,プッシュスイッチの2がONの時,デューティー比50%で点灯,プッシュスイッチの3がONの時,デューティー比25%で点灯する。(リスト2.2の説明参照)それ以外の状況ではLED消灯するプログラム。
(3)ファイルh8-01.hの最初の説明を読んでプッシュスイッチ関係の関数の機能をまとめて説明しなさい。

4.6    リミットスイッチプログラム

リスト 6.1
リミットスイッチプログラム

/****************************************
1ビット外部入力(リミットスイッチ) (P4-2)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
リミットスイッチ関係 (P4-2の制御)

void initLimitSW(void)
 リミットスイッチの初期化 (ポート4第2ビットの初期化)
int checkLimitSW(void)
 リミットスイッチ の状態を調べる
 押されていたら1、そうでなかったら0を返す
****************************************/

void initLimitSW(void)
{
    P4DDR &= 0xfb; /*P4-2は入力*/
    P4.DDR = P4DDR;
    P4.PCR.BYTE |=  0x04; /*P4-2はプルアップ */
}

int checkLimitSW(void)
{
    /*スイッチがNORMALY CLOSEになっている*/
    int tmp,ret=0;
    tmp=P4.DR.BYTE;
    if (tmp&0x04) ret=1;
    return ret;
}

main()
{
    const static char status[][5]={"OFF","ON "};
    initSCI1();
    initLimitSW();
    SCI1_printf("       **          Limit Switch          **\n");
    while (1) {
        SCI1_printf("LimitSW:%s  \r",status[checkLimitSW()]);
    }
}

図8 リミットスイッチ

練習問題6 次のプログラムを作りなさい。

(1)起動後,何回リミットスイッチがON−OFFしたかを表示しつづける

4.7    電球点滅プログラム

リスト 7.1
電球点滅プログラム
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
1ビット出力(パワーMOSFET駆動豆電球) (P5-2)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
パワーMOSFET駆動豆電球関係 (P5-2の制御)

void initMOSFET(void)
 パワーMOSFET出力の初期化 (ポート5第2ビットの初期化)
void turnOnMOSFET(void)
 パワーMOSFET出力ON
void turnOffMOSFET(void)
 パワーMOSFET出力OFF
****************************************/

void initMOSFET(void)
{
    P5DDR |=  0x4; /*P5-2は出力*/
    P5.DDR=P5DDR;
}

/*
void turnOnMOSFET(void)
{
    P5.DR.BYTE |= 4;
}

void turnOffMOSFET(void)
{
    P5.DR.BYTE &= 0xfb;
}
*/
#define turnOnMOSFET() (P5.DR.BYTE |= 4)
#define turnOffMOSFET() (P5.DR.BYTE &= 0xfb)

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

main()
{
    unsigned int count=0;
    initSCI1();
    initMOSFET();
    SCI1_printf("       ** Bulb with Power MOS FET winking **\n");
    while (1) {
        SCI1_printf("count=%5u \n",count++);
        turnOnMOSFET();  /*パワーMOSFET駆動豆電球のON*/
        msecwait(500);
        turnOffMOSFET();  /*パワーMOSFET駆動豆電球のOFF*/
        msecwait(500);
  }
}

リスト 7.2
プッシュスイッチ指令,タイマ割り込みによる電球のPWM光度制御
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
1ビット出力(パワーMOSFET駆動豆電球) (P5-2)
割り込み周期1msecの割り込み関数
PWM駆動による「パワーMOSFET駆動豆電球」の光度制御
プッシュスイッチによる指令
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
パワーMOSFET駆動豆電球関係 (P5-2の制御)

void initMOSFET(void)
 パワーMOSFET出力の初期化 (ポート5第2ビットの初期化)
void turnOnMOSFET(void)
 パワーMOSFET出力ON
void turnOffMOSFET(void)
 パワーMOSFET出力OFF
****************************************/

void initMOSFET(void)
{
    P5DDR |=  0x4; /*P5-2は出力*/
    P5.DDR=P5DDR;
}

/*
void turnOnMOSFET(void)
{
    P5.DR.BYTE |= 4;
}

void turnOffMOSFET(void)
{
    P5.DR.BYTE &= 0xfb;
}
*/
#define turnOnMOSFET() (P5.DR.BYTE |= 4)
#define turnOffMOSFET() (P5.DR.BYTE &= 0xfb)

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

volatile int pwmValue=0;
const int pwmIndex[]={1,2,4,8};
const char status[][5]={"OFF","ON "};

main()
{
    int i,value;
    initSCI1();
    initPushSW();
    initMOSFET();
    initTimer1Int(1000); /*時間割り込み1000μsec ch1使用*/
    E_INT();             /*CPU割り込み許可*/
    startTimer1();      /*時間割り込みタイマスタート ch1*/
    SCI1_printf("       ** Bulb with Power MOS FET controled by PushSW **\n");
    SCI1_printf("!! Press any push switch !!\n");
    while (1) {
        value=0;
        for (i=0;i<4;i++) {
            if (checkPushSW(i)) value=pwmIndex[i];
            SCI1_printf("bit%d:%s ",i,status[checkPushSW(i)]);
        }
        pwmValue=value;
        SCI1_printf("pwmValue= %d/8\r",pwmValue);
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int tick=0;
    if (tick<pwmValue) {
        turnOnMOSFET();
    } else {
        turnOffMOSFET();
    }
    tick++;
    if (tick==8) tick=0;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

練習問題7 次のプログラムを作りなさい。

(1)すべてのプッシュスイッチがOFFの時,0.5秒周期で電球を点滅,プッシュスイッチの1がONの時,1秒周期で電球を点滅,プッシュスイッチの2がONの時,2秒周期で電球を点滅させる。それ以外の状態ではLEDはすべて消灯。
(2)リスト7.2のプログラムの動作チェックを行いなさい。プログラムで想定されているすべての入力を行ない,その時の様子を報告しなさい。
なお,それぞれの場合の理論上のデューティ比を求めなさい。

 

4.8    DAコンバータプログラム

DAコンバータ(Digital Analogue Converter)とはコンピュータ内部の数値(ディジタル量)をコンピュータ外部に電圧(アナログ量)として出力する機能である。H8/3048には2チャンネルのDAコンバータがある。装置ではADコンバータチャンネル0に出力している。(図3参照)
以下のプログラムではシリアルインタフェイスに接続されたPCのターミナルソフトでキー入力を行ない,0から255までの値を入力すると「DAC out」(図9.2参照)に約0Vから約5Vまでが電圧として出力される。これはH8/3048のDAコンバータが8ビット構成であることに起因している。

図9.1 DAコンバータ

図9.2 DAコンバータの出口

リスト 8.1
DAコンバータプログラム
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
DAコンバータ (DA0)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
DAコンバータ (DA0)
void initDAC(unsigned char mode)
 DAコンバータの初期化
 mode 1: ch0のみ初期化
 mode 2: ch1のみ初期化
 mode 3: ch0,1両方とも初期化

void putDAC(unsigned char ch, unsigned char data)
 DA出力 ch:チャネル data:データ

void initDAC0(void)
 DAコンバータの初期化 ch0のみに特化したバージョン

void putDAC0(unsigned char data)
 DA出力 data:データ ch0のみに特化したバージョン

void initDAC1(void)
 DAコンバータの初期化 ch1のみに特化したバージョン

void putDAC1(unsigned char data)
 DA出力 data:データ ch1のみに特化したバージョン

data    出力電圧
  0  →   0V
255  →   5V

****************************************/

void initDAC(unsigned char mode)
{
    mode&=3;
    mode<<=6;
    DA.DR0 = 0;
    DA.DR1 = 0;
    DA.CR.BYTE |= mode;
}

void putDAC(unsigned char ch, unsigned char data)
{
    if(ch==0)
        DA.DR0 = data;
    else if(ch==1)
        DA.DR1 = data;
}

void initDAC0(void)
{
    DA.DR0 = 0;
    DA.CR.BYTE |= 0x40;
}

void putDAC0(unsigned char data)
{
    DA.DR0 = data;
}

void initDAC1(void)
{
    DA.DR1 = 0;
    DA.CR.BYTE |= 0x80;
}

void putDAC1(unsigned char data)
{
    DA.DR1 = data;
}

main()
{
    int x;
    initSCI1();
    SCI1_printf("       **          DA Converter          **\n");
    initDAC0();
    while (1) {
        x=getIntSCI1("DA value(0..255) =");
        putDAC0(x&0xff);
        SCI1_printf("   Measure voltage at the DAC output.\n");
    }
}

 ●画面への表示をそのままファイル化する方法

練習問題8

(1)キーボードから与えた0〜255の数値に従って何ボルトがDAC出力端子に出ているか表にまとめなさい。
ただし,値は0,8,16,24,32,...のように8の倍数と255について試しなさい。

 

4.9    ADコンバータプログラム

ADコンバータ(Analogue Digital Converter)とはDAコンバータとは逆に,与えられた電圧(アナログ量)をコンピュータ内部の数値(ディジタル量)をとして入力する機能である。H8/304は8チャンネルのADコンバータが備わっている。各ADコンバータの分解能は10ビットであり,入力電圧が0Vから5Vまで変化すると取り込まれた値は0から1023まで変化する。
なお次のプログラムは,DAコンバータチャンネル0から電圧出力しながら,ADコンバータチャンネル0が入力するので,図10のようにこの2つを直結すると,DAコンバータへの出力値とADコンバータ入力値がターミナル上に表示される。

図10.1 DAコンバータ出力をADコンバータで読み込む
このプログラム起動時には図のようにDAC出力とADC入力を直結すること

図10.2 DAコンバータの出口とADコンバータの入り口

リスト 9.1
ADコンバータプログラム
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
ADコンバータ (AN0)
DAコンバータ (DA0)による電圧チェック
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
DAコンバータ (DA0)
void initDAC(unsigned char mode)
 DAコンバータの初期化
 mode 1: ch0のみ初期化
 mode 2: ch1のみ初期化
 mode 3: ch0,1両方とも初期化

void putDAC(unsigned char ch, unsigned char data)
 DA出力 ch:チャネル data:データ

void initDAC0(void)
 DAコンバータの初期化 ch0のみに特化したバージョン

void putDAC0(unsigned char data)
 DA出力 data:データ ch0のみに特化したバージョン

void initDAC1(void)
 DAコンバータの初期化 ch1のみに特化したバージョン

void putDAC1(unsigned char data)
 DA出力 data:データ ch1のみに特化したバージョン

data    出力電圧
  0  →   0V
255  →   5V

****************************************/

void initDAC(unsigned char mode)
{
    mode&=3;
    mode<<=6;
    DA.DR0 = 0;
    DA.DR1 = 0;
    DA.CR.BYTE |= mode;
}

void putDAC(unsigned char ch, unsigned char data)
{
    if(ch==0)
        DA.DR0 = data;
    else if(ch==1)
        DA.DR1 = data;
}

void initDAC0(void)
{
    DA.DR0 = 0;
    DA.CR.BYTE |= 0x40;
}

void putDAC0(unsigned char data)
{
    DA.DR0 = data;
}

void initDAC1(void)
{
    DA.DR1 = 0;
    DA.CR.BYTE |= 0x80;
}

void putDAC1(unsigned char data)
{
    DA.DR1 = data;
}

/***************************************
ADコンバータ (単一モード)

void initADC(void)
 ADC初期化ADC単一モード初期化(インタラプト禁止,変換時間=134ステート)

unsigned int getADC(unsigned char ch)
 AD変換結果の取得
 この関数を呼び出した時にAD変換命令が作られ,
 変換終了まで待ち,AD変換値を取得する。
 chは0,1,2,3,4,5,6,7に対応している。

--------------------
void initADC0(void)
 ADC初期化ADC単一モード初期化(ch0のみに特化したバージョン)

unsigned int getADC0(void)
 AD変換結果の取得
 この関数を呼び出した時にAD変換命令が作られ,
 変換終了まで待ち,AD変換値を取得する。
 ch0のみに特化したバージョン
--------------------
void initADC1(void)
 ADC初期化ADC単一モード初期化(ch1のみに特化したバージョン)

unsigned int getADC1(void)
 AD変換結果の取得
 この関数を呼び出した時にAD変換命令が作られ,
 変換終了まで待ち,AD変換値を取得する。
 ch1のみに特化したバージョン
 

出力電圧    data
  0V  →      0
  5V  →   1023

****************************************/

void initADC(void)
{
    AD.CSR.BIT.ADF= 0;   /*エンドフラグをクリア*/
    AD.CSR.BIT.ADIE=0;   /*インタラプト禁止*/
    AD.CSR.BIT.ADST=0;   /*スタート停止*/
    AD.CSR.BIT.SCAN=0;   /*単一モード*/
    AD.CSR.BIT.CKS= 1;   /*変換時間=134ステート*/
}

unsigned int getADC(unsigned char ch)
{
    AD.CSR.BIT.CH=  ch;         /*チャネル設定 */
    AD.CSR.BIT.ADST = 1;        /*AD変換スタート*/
    while(AD.CSR.BIT.ADF == 0); /*変換終了まで待つ*/ 
    AD.CSR.BIT.ADF= 0;          /*エンドフラグをクリア*/
                                /* ADSTは自動的に0になっている*/
    ch&=3;
    return *(&AD.DRA+ch)>>6;
}

void initADC0(void)
{
    AD.CSR.BIT.ADF= 0;   /*エンドフラグをクリア*/
    AD.CSR.BIT.ADIE=0;   /*インタラプト禁止*/
    AD.CSR.BIT.ADST=0;   /*スタート停止*/
    AD.CSR.BIT.SCAN=0;   /*単一モード*/
    AD.CSR.BIT.CKS= 1;   /*変換時間=134ステート*/
    AD.CSR.BIT.CH=  0;         /*チャネル設定 */
}

unsigned int getADC0(void)
{
    AD.CSR.BIT.ADST = 1;        /*AD変換スタート*/
    while(AD.CSR.BIT.ADF == 0); /*変換終了まで待つ*/ 
    AD.CSR.BIT.ADF= 0;          /*エンドフラグをクリア*/
                                /* ADSTは自動的に0になっている*/
    return AD.DRA>>6;
}

void initADC1(void)
{
    AD.CSR.BIT.ADF= 0;   /*エンドフラグをクリア*/
    AD.CSR.BIT.ADIE=0;   /*インタラプト禁止*/
    AD.CSR.BIT.ADST=0;   /*スタート停止*/
    AD.CSR.BIT.SCAN=0;   /*単一モード*/
    AD.CSR.BIT.CKS= 1;   /*変換時間=134ステート*/
    AD.CSR.BIT.CH=  1;         /*チャネル設定 */
}

unsigned int getADC1(void)
{
    AD.CSR.BIT.ADST = 1;        /*AD変換スタート*/
    while(AD.CSR.BIT.ADF == 0); /*変換終了まで待つ*/ 
    AD.CSR.BIT.ADF= 0;          /*エンドフラグをクリア*/
                                /* ADSTは自動的に0になっている*/
    return AD.DRB>>6;
}

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

main()
{
    unsigned int x=0,y;
    initSCI1();
    initDAC0();
    initADC0();
    SCI1_printf("       **   AD Converter with DA converter check   **\n");
    SCI1_printf("The DA converter generates voltage"
                " from 0V to 5V every 1sec.\n");
    SCI1_printf("If DAC output is connects to the ADC input directly,\n");
    SCI1_printf("  the relation between ADC and DAC can be observed.\n");
    while (1) {
        putDAC0(x);
        msecwait(1000);
        y=getADC0();
        SCI1_printf("DAC:%3d ==> ADC:%4d (ADC/4:%3d) \n",x,y,(y+2)>>2);
        x+=0x20;
        if (x==0x100) x=0xff;
        else if (x==0x11f) x=0;
    }
}

 

練習問題9

(1)ADコンバータ単体で動作するプログラムを作りなさい。 0.2秒間隔でADC結果を表示するプログラムを作成しなさい。
ADC入力端子(もし,図10のように直結されていたらこれをはずしておくこと) に0Vから1Vのステップで5Vまでをかけてどのような値が取得できたか表にまとめなさい。

重要な注意事項

ADコンバータの利用に関して重要な注意事項があります。これを守らないとADコンバータを壊します。
●電源電圧以上の電圧をADコンバータへの入力を与えないこと
●電源が切れている時,マイコンへプログラム書き込みの時にはADコンバータへの入力を与えないこと

(1)「CPUの電源」がONになってから「ADコンバータへの入力」を与え,「ADコンバータへの入力」を取り去ってから「CPUの電源」をOFFにすること
「CPUの電源」がOFFの時の電源電圧は0Vなので,この状態で「ADコンバータへの入力」を与えると,電源電圧以上の「ADコンバータへの入力」を与えたことになってしまいます。
(2)「CPUの電源」がONになっている場合,電源電圧は5Vなので,「ADコンバータへの入力」は0Vから5Vの範囲を厳守してください。

 

4.10 位相カウンタによるインクリメンタル型ロータリエンコーダのパルス計測

軸の回転角度を測定するセンサに,光学式ロータリエンコーダがある。これは回転軸に,スリットのある円板を取り付け,発光器と光センサ間にこの円板を置き,軸が回転するとセンサへの光が透過・遮断を繰り返すようにする。その結果光センサ出力は1−0を繰返し,1−0の繰返し数をカウントすると軸の回転角が読み取れるようになっている。この構造をもつロータリエンコーダはインクリメンタル型ロータリエンコーダと呼ばれる。さらに,位相の異なる位置にもう1つの発光器と光センサをつけることにより,2相の光センサ出力が得られ。回転方向もわかるようになっている。
H8/3048には2相のセンサ出力で,自動的にアップカウントダウンカウントを行なうカウンタがあり,これは位相カウンタと呼ばれている。このカウンタにインクリメンタル型ロータリエンコーダの2相出力信号を取り込むことによって,回転軸の角度を検出できる。
装置には,1回転すると200カウントするロータリエンコーダが付属しており,内部で4倍カウントするので,軸の1回転を800カウントとして読み込む。

次のプログラム(リスト10.1)を起動し,ロータリエンコーダを手で回転させると,角度変位が読み取れる。ただし1パルスは1/800回転である。

 

図11 インクリメンタル型ロータリエンコーダ

リスト 10.1
位相カウンタによるインクリメンタル型ロータリエンコーダのパルス計測
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
インクリメント型2相ロータリエンコーダ信号カウント (ITU2)
ロータリエンコーダAB信号のカウント
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
インクリメント型2相ロータリエンコーダ信号カウント (ITU2)
void initPhaseCounter(void)
 2相信号カウンタ初期化

int getPhaseCounter(void)
 2相信号カウンタ値取得

void clearPhaseCounter(void)
 2相信号カウンタ値クリア

****************************************/

void initPhaseCounter(void)
/*ITU chanel2を使用*/
{
    ITU.TMDR.BYTE |= 0x40; /*MDF->1 ITU2:counter mode*/
    ITU.TSTR.BIT.STR2=1;
    ITU2.TCNT=0;
}

/*
int getPhaseCounter(void)
{
    return ITU2.TCNT;
}

void clearPhaseCounter(void)
{
    ITU2.TCNT=0;
}
*/
#define getPhaseCounter() (ITU2.TCNT)
#define clearPhaseCounter() (ITU2.TCNT=0)

main()
{
    int x=0;
    initSCI1();
    initPhaseCounter();
    clearPhaseCounter();
    SCI1_printf("       ** Phase Counter for Rotary Encoder **\n");
    while (1) {
        x=getPhaseCounter();
        SCI1_printf("PhaseCounter=%6d \r",x);
    }
}

タイマ割り込みにより,一定間隔でインクリメンタル型ロータリエンコーダの角度を読み取っていくと,前回の角度との差を計算することが出来る。この差は「差分」といって,回転速度を意味する。例えばリスト10.2では1/100秒間の角度変化を読み取っている。

リスト 10.2
位相カウンタによるインクリメンタル型ロータリエンコーダのパルス計測とカウント差分算出
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
インクリメント型2相ロータリエンコーダ信号カウント (ITU2)
ロータリエンコーダAB信号のカウント
タイマ割り込みを用いたカウント差分(速度に対応)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
インクリメント型2相ロータリエンコーダ信号カウント (ITU2)
void initPhaseCounter(void)
 2相信号カウンタ初期化

int getPhaseCounter(void)
 2相信号カウンタ値取得

void clearPhaseCounter(void)
 2相信号カウンタ値クリア

****************************************/

void initPhaseCounter(void)
/*ITU chanel2を使用*/
{
    ITU.TMDR.BYTE |= 0x40; /*MDF->1 ITU2:counter mode*/
    ITU.TSTR.BIT.STR2=1;
    ITU2.TCNT=0;
}

/*
int getPhaseCounter(void)
{
    return ITU2.TCNT;
}

void clearPhaseCounter(void)
{
    ITU2.TCNT=0;
}
*/
#define getPhaseCounter() (ITU2.TCNT)
#define clearPhaseCounter() (ITU2.TCNT=0)

volatile int difference=0; /*カウント差分(10msec間)*/

main()
{
    int position=0;
    initSCI1();
    initPhaseCounter();
    clearPhaseCounter();
    initTimer1Int(10000); /*時間割り込み10000μsec ch1使用*/
    E_INT();             /*CPU割り込み許可*/
    startTimer1();      /*時間割り込みタイマスタート ch1*/
    SCI1_printf("       ** Phase Counter for Rotary Encoder **\n");
    while (1) {
        position=getPhaseCounter();
        SCI1_printf("Position=%6d difference=%4d\n"
        ,position,difference);
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    static int count=0;
    static int old=0;
    count=getPhaseCounter();
    difference=count-old;
    old=count;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

 ●画面への表示をそのままファイル化する方法

練習問題10

(1)リスト10.1のプログラムで,手でモータ軸を1周回転させて,カウンタ値がいくつ変化するか観察し,結果をまとめなさい。
このカウンタ値をxとすると,これはy[deg](度)であり,z[rad]である。yとzをxで表せ。
(2)リスト10.2では,差分が表示されるが,この表示の単位はどのように表示すべきか。また[deg/sec],[rad/sec]への換算式を示しなさい。
(3)現在使用中のロータリエンコーダの銘板には○○○P/R(Pulses/Revolution)と書いてある。どういう意味か
(H8/3048CPUでは1パルスを4分割してカウントしている。銘板上のパルス数と測定されたパルス数のは4倍の関係になっている)

 

4.11 モータ駆動プログラム

モータを駆動するため,PWM信号をITUチャンネル3を用いて発生させ,ポート4のビット0,1で回転方向を決めている。使用しているモータドライバはTA8429である。

PWMとはパルス幅変調のことで,リスト2.2に説明がある。人間の感覚ではわからないくらいの高速なモータON−OFF動作を行ない,見かけ上モータへ与える電圧を変化させているようにしている。1回のON−OFF動作にかかる時間がPWM周期であり,周期中のONになっている時間の比がデューティ比である。リスト11.1のプログラムではPWM周期が1/16000秒(0.0000625秒)でデューティ比は「「キーボード入力したPWMValue」÷1000」で設定される。適当なPWM値を与えて,モータを駆動している時に,CN1-16のピンをオシロスコープで観察するとPWM信号が観察できる。

 

Port4 Bit0 Port4 Bit1 ITOCA3 TA8429Hの出力
0 0 何でもよい 回転しない(出力0)
0 1 PWM信号 正転PWM駆動
1 0 PWM信号 逆転PWM駆動
1 1 デューティ比1のPWM信号 ショートブレーキ

図12 モータ駆動とモータドライバIC「TA8429」

ITU内部カウンタは16MHzのCPUクロックをカウントしている。
このカウンタは,カウンタ値が値Aに一致するとクリアされ0に戻る。
カウンタ値が,値Bより小さい時PWM信号はHとなり,値Bより大きい時PWM信号はLになる。
値Aはプログラム中では初期化関数init_pwm3()へ引数で設定される。
 1つのプログラムでは1回だけ設定される。
値Bはプログラム中では関数driveMotor()への引数で設定される。
PWM信号はITOCA3の信号として,CPUのピン2,CPUカードのCN1-16へ出力される。

CPUクロック周波数=16MHzなのでクロック周期は0.0625μsである。
プログラム中ではA=1000で設定されているため,PWM周期T1=62.5μsである。
プログラム中でB=900が与えられた時,デューティ比は0.9となる。

図12-B PWM信号の発生メカニズム

 

リスト 11.1
モータ駆動プログラム
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
PWM信号+回転方向信号出力 (ITU3,P4-0,P4-1)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
PWM信号+回転方向信号出力 (ITU3,P4-0,P4-1)
void init_pwm3(int pwmMax)
 モータ駆動PWM信号発生機構の初期化
 ITU3はPWM信号を発生し,P4-0,1はモータの回転方向を指示する
 int pwmMAXはPWM周期を規定する。PWM周期 T は
 T = M/(16*10^6) [sec] となる。 M:pwmMAX

void driveMotor(int pwm)
 PWM駆動指令を与える
 -pwmMAX<pwm<pwmMAXを与えるとよい。
 ただし,この範囲を超える値を与えてもよい
 負のpwm値は逆転を意味する

void brakeMotor(void)
 モータドライバICの仕様に従って,ショートブレーキ状態を作る
****************************************/

void init_pwm3(int pwmMax)
{
    /*P4-0,P4-1初期化(P4-0,P4-1で回転方向を設定するため) */
    P4DDR|=0x03;  /*下位2ビットを出力に*/
    P4.DDR=P4DDR;
    P4.DR.BYTE=0x0; /*初期値 b0=cw,b1=ccw 正論理*/

    /*ITU3の初期化*/
    ITU3.TCR.BIT.TPSC=0;   /*内部クロックφでカウント*/
    ITU3.TCR.BIT.CKEG=0;   /*立ち上がりエッジでカウント*/
    ITU3.TCR.BIT.CCLR=1;   /*GRAのコンペアマッチでTCNTをクリア*/
    ITU3.GRA=pwmMax-1;     /*GRAの値(GRB=GRAのときPWMが100%)をPWM_MAXに設定*/
    ITU3.GRB=0;            /*GRBの値を0に設定(=PWM0%)*/
    ITU.TMDR.BIT.PWM3=1;   /*ITUのPWMに使うchをPWMモードに設定*/
    ITU3.TIOR.BIT.IOB=0;   /*TIOCBにPWM信号を出力しないように設定*/
    ITU.TSTR.BIT.STR3=1;   /*カウントスタート(PWM信号が出力される)*/
}

void driveMotor(int pwm)
{
/*ITU3.GRA=pwmの時デューティ比100%で動作してほしい*/
/*しかし仕様上デューティ比100%を作る場合はGRA<GRBにすることになっている*/
    if (0<pwm) {
        P4.DR.BIT.B0=1;
        P4.DR.BIT.B1=0;
        pwm--;
        if (ITU3.GRA==pwm) pwm--; /*ITU3.GRA==pwm対策*/
        ITU3.GRB=pwm;
    } else if (pwm<0) {
        P4.DR.BIT.B0=0;
        P4.DR.BIT.B1=1;
        pwm=-pwm-1;
        if (ITU3.GRA==pwm) pwm--; /*ITU3.GRA==pwm対策*/
        ITU3.GRB=pwm;
    } else {
        P4.DR.BIT.B0=0;
        P4.DR.BIT.B1=0;
        ITU3.GRB=0;
    }
}

void brakeMotor(void)
{
/*ITU3.GRA=pwmの時デューティ比100%で動作してほしいが,GRA<GRBで100%になる*/
    P4.DR.BIT.B0=1;
    P4.DR.BIT.B1=1;
    ITU3.GRB=ITU3.GRA+1;
}

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

#define PWM_MAX 1000

main()
{
    int x=0,old=0;
    int max=PWM_MAX;
    initSCI1();
    init_pwm3(max);
    SCI1_printf("       **      Motor Drive with PWM      **\n");
    SCI1_printf("PWM value should be in the range of -%d .. %d.\n",max,max);
    while (1) {
        SCI1_printf("PWM value(-%d..%d) =",max,max);
        x=getIntSCI1("");
        if ((x<0&&0<old)||(0<x&&old<0)) {
            brakeMotor();
            msecwait(500);
        }
        old=x;
        driveMotor(x);
    }
}

次のプログラムはPWMでモータを駆動し,一定時間ごとの角度を表示するプログラムである。
一定時間を確実にするためにタイマ割り込みを利用している。
タイマ割り込み関数内で角度を読み取り,メイン側にデータ表示要求を出している。
メイン側は,割り込み関数が表示要求を出していることがわかったら,表示するようになっている。
なお,msec単位の時刻もわかるような変数timecountを持っている。10msecごとのタイマ割り込みなので
タイマ割り込み関数内でtimecountは10ずつ増加している。

リスト 11.2
モータ駆動および定期角度センサ取り込み表示プログラム
色の薄い部分のプログラムは関数の機能だけ理解すればよい。

/****************************************
PWM駆動,定期角度センサ取り込み
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
PWM信号+回転方向信号出力 (ITU3,P4-0,P4-1)
void init_pwm3(int pwmMax)
 モータ駆動PWM信号発生機構の初期化
 ITU3はPWM信号を発生し,P4-0,1はモータの回転方向を指示する
 int pwmMAXはPWM周期を規定する。PWM周期 T は
 T = M/(16*10^6) [sec] となる。 M:pwmMAX

void driveMotor(int pwm)
 PWM駆動指令を与える
 -pwmMAX<pwm<pwmMAXを与えるとよい。
 ただし,この範囲を超える値を与えてもよい
 負のpwm値は逆転を意味する

void brakeMotor(void)
 モータドライバICの仕様に従って,ショートブレーキ状態を作る
****************************************/

void init_pwm3(int pwmMax)
{
    /*P4-0,P4-1初期化(P4-0,P4-1で回転方向を設定するため) */
    P4DDR|=0x03;  /*下位2ビットを出力に*/
    P4.DDR=P4DDR;
    P4.DR.BYTE=0x0; /*初期値 b0=cw,b1=ccw 正論理*/

    /*ITU3の初期化*/
    ITU3.TCR.BIT.TPSC=0;   /*内部クロックφでカウント*/
    ITU3.TCR.BIT.CKEG=0;   /*立ち上がりエッジでカウント*/
    ITU3.TCR.BIT.CCLR=1;   /*GRAのコンペアマッチでTCNTをクリア*/
    ITU3.GRA=pwmMax-1;     /*GRAの値(GRB=GRAのときPWMが100%)をPWM_MAXに設定*/
    ITU3.GRB=0;            /*GRBの値を0に設定(=PWM0%)*/
    ITU.TMDR.BIT.PWM3=1;   /*ITUのPWMに使うchをPWMモードに設定*/
    ITU3.TIOR.BIT.IOB=0;   /*TIOCBにPWM信号を出力しないように設定*/
    ITU.TSTR.BIT.STR3=1;   /*カウントスタート(PWM信号が出力される)*/
}

void driveMotor(int pwm)
{
/*ITU3.GRA=pwmの時デューティ比100%で動作してほしい*/
/*しかし仕様上デューティ比100%を作る場合はGRA<GRBにすることになっている*/
    if (0<pwm) {
        P4.DR.BIT.B0=1;
        P4.DR.BIT.B1=0;
        pwm--;
        if (ITU3.GRA==pwm) pwm--; /*ITU3.GRA==pwm対策*/
        ITU3.GRB=pwm;
    } else if (pwm<0) {
        P4.DR.BIT.B0=0;
        P4.DR.BIT.B1=1;
        pwm=-pwm-1;
        if (ITU3.GRA==pwm) pwm--; /*ITU3.GRA==pwm対策*/
        ITU3.GRB=pwm;
    } else {
        P4.DR.BIT.B0=0;
        P4.DR.BIT.B1=0;
        ITU3.GRB=0;
    }
}

void brakeMotor(void)
{
/*ITU3.GRA=pwmの時デューティ比100%で動作してほしいが,GRA<GRBで100%になる*/
    P4.DR.BIT.B0=1;
    P4.DR.BIT.B1=1;
    ITU3.GRB=ITU3.GRA+1;
}

/***************************************
インクリメント型2相ロータリエンコーダ信号カウント (ITU2)
void initPhaseCounter(void)
 2相信号カウンタ初期化

int getPhaseCounter(void)
 2相信号カウンタ値取得

void clearPhaseCounter(void)
 2相信号カウンタ値クリア

****************************************/

void initPhaseCounter(void)
/*ITU chanel2を使用*/
{
    ITU.TMDR.BYTE |= 0x40; /*MDF->1 ITU2:counter mode*/
    ITU.TSTR.BIT.STR2=1;
    ITU2.TCNT=0;
}

/*
int getPhaseCounter(void)
{
    return ITU2.TCNT;
}

void clearPhaseCounter(void)
{
    ITU2.TCNT=0;
}
*/
#define getPhaseCounter() (ITU2.TCNT)
#define clearPhaseCounter() (ITU2.TCNT=0)

#define PWM_MAX 1000

volatile int pulsecount;         /*割り込み時位置*/
volatile int requestDisplaydata; /*表示リクエスト*/
volatile int timecount;          /*時刻を表す変数単位msec*/

main()
{
    int x=0;
    int max=PWM_MAX;
    initSCI1();
    initPhaseCounter();  /*Rotaryencoder counter ITUch2初期化*/
    init_pwm3(max);
    initTimer1Int(10000); /* 10msecごとの割り込み関数起動を設定*/
    E_INT();             /*CPU割り込み許可*/
    SCI1_printf("       **      Motor Drive with PWM      **\n");
    SCI1_printf("PWM value should be in the range of -%d .. %d.\n",max,max);
    while (1) {
        SCI1_printf("PWM value(-%d..%d) =",max,max);
        x=getIntSCI1("");
        timecount=-10;
        requestDisplaydata=0;
        clearPhaseCounter();
        SCI1_printf("time[msec] position[pulse]\n");
        startTimer1();      /*時間割り込みタイマスタート ch1*/
        while (timecount!=0);
        driveMotor(x);
        while (timecount<=1000) {
            if (requestDisplaydata) {
                SCI1_printf("%10d %10d\n",timecount,pulsecount);
                requestDisplaydata=0;
            }
        }
        stopTimer1();
        brakeMotor();
    }
}

/*タイマ割り込み関数*/
#pragma interrupt
void int_imia1() /*割り込みルーチン この名前はリンカスクリプトで決まっている*/
{
    pulsecount=getPhaseCounter();
    requestDisplaydata=1;
    timecount+=10;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

実行例
PWM value(-1000..1000) =1000
time[msec] position[pulse]
         0          0
        10          4
        20         26
        30         59
        40        103
        50        153
        60        206
        70        263
        80        322
        90        384
       100        446
       110        510
       120        573
       130        637
    このあと省略

リスト11.2では,モータ指令値の変更(ブレーキも同様)は非割り込み関数側で処理していた。
リスト11.3のように,非割り込み関数側は,表示に専念し,モータへの指令を割り込み関数内でのみ行うようにすると,これ以降のプログラミングの役に立つようになる。リスト11.3はリスト11.2の後ろの部分である。

リスト11.3
#define PWM_MAX 1000

volatile int pulsecount;         /*割り込み時位置*/
volatile int requestDisplaydata; /*表示リクエスト*/
volatile int timecount;          /*時刻を表す変数 単位msec*/
volatile int pwmvalue;           /*PWM指令値*/

main()
{
    int max=PWM_MAX;
    initSCI1();
    initPhaseCounter();  /*Rotaryencoder counter ITUch2初期化*/
    init_pwm3(max);
    initTimer1Int(10000); /* 10msecごとの割り込み関数起動を設定*/
    E_INT();             /*CPU割り込み許可*/
    SCI1_printf("       **      Motor Drive with PWM      **\n");
    SCI1_printf("PWM value should be in the range of -%d .. %d.\n",max,max);
    while (1) {
        SCI1_printf("PWM value(-%d..%d) =",max,max);
        pwmvalue=getIntSCI1("");
        timecount=-10;
        requestDisplaydata=0;
        clearPhaseCounter();
        SCI1_printf("time[msec] position[pulse]\n");
        startTimer1();      /*時間割り込みタイマスタート ch1*/
        while (timecount<=1010) {
            if (requestDisplaydata) {
                SCI1_printf("%10d %10d\n",timecount,pulsecount);
                requestDisplaydata=0;
            }
        }
        stopTimer1();
    }
}

/*タイマ割り込み関数*/
/*この関数名は変更できない。プログラム中で1つしか使えない。*/
void interrupt_cfunc()
{
    timecount+=10;
    pulsecount=getPhaseCounter();
    if (timecount==0) {
        driveMotor(pwmvalue);
    } else if (timecount==1000) {
        brakeMotor();
    }
    requestDisplaydata=1;
    ITU1.TSR.BIT.IMFA=0; /*Clear IMFA これは自分の責任で行なう*/
}

 ●画面への表示をそのままファイル化する方法

練習問題11A

(1)リスト11.1のプログラムを次の仕様のように変更しなさい。
 1)PWM指令値を入力したら,そのPWM指令値で0.50秒間だけモータを駆動し,モータを停止する。
 2)モータが停止したら次のPWM指令値が入力できる。
 3)「1)2)」の作業は何回でも繰返し出来るようにしなさい。

(2)リスト11.2のプログラムをさらに次の仕様のように変更しなさい。
 1)毎回モータ駆動直前に角度センサのカウンタをクリアする。
 2)モータ駆動は0.50秒間とし,その後は惰性で回転させる。
 3)モータ起動後0.01秒ごとに,角度,角度差分を表示する。
  (この表示はキャプチャして,Excelでグラフ化し,これも提出すること)
 4)角度差分は0.01秒間の差分とし,正確な計測のため,タイマ割り込みを用いる。
 5)角度,角度差分の表示はモータ起動後1.00秒間とする。
 6)角度,角度差分の表示は割り込み関数内で行なってはいけない。
  (割り込み関数は出来るだけ作業を短時間に終わりたいからである)

練習問題11B
(3)リスト11.1で使用しているハードウェアカウンタは16ビットなので,±32768を超える値を検出することが出来ない。またこの境界を超える瞬間に速度(差分)を正しく求めることが出来ない。
32ビットの範囲で正しくカウントできるように工夫し,32bitのソフトウェアカウンタを構成しなさい。 追加説明
(ヒントlong intのカウンタ変数を用意する。1/100秒に10000カウント以上変化したら変なので補正を考える。)
そして次の3つの関数を作りなさい。
void initVirtualPhaseCounter(void)
 ソフトウェア2相信号カウンタ初期化
 内部でinitPhaseCounter()を使ってもよい

long int getVirtualPhaseCounter(void)
 ソフトウェア2相信号カウンタ値取得
 内部でgetPhaseCounter()を使ってもよい

void clearVirtualPhaseCounter(void)
 ソフトウェア2相信号カウンタ値クリア
 内部でclearPhaseCounter()を使ってもよい

練習問題11C     実行結果例(ヒントもあり)

(1)次の仕様のプログラムを作りなさい。
 1)カウンタ値0の位置からモータを駆動し,カウンタ値が800の位置でモータを止める。
 2)モータ駆動直前に角度センサのカウンタをクリアする。
 3)正確に800の位置に止められなくてもよいが,できるだけ800に近い位置に止める。
 4)この作業は何回でも繰返し出来るようにしなさい。
 5)モータ起動時および起動後0.01秒ごとに,その時の時刻,PWM値,角度,角度差
   分を表示する。
  (この表示はキャプチャして,Excelでグラフ化し,これも提出すること)
 6)角度はその時刻のカウンタ値,角度差分は0.005秒間のカウンタ値の差分とする。
 7)時刻,PWM値,角度,角度差分の表示はモータ起動1秒後までとする。
 8)角度,角度差分の表示は割り込み関数内で行なってはいけない。
  (割り込み関数は出来るだけ作業を短時間に終わりたいからである)
 9)PWM値の更新は0.005秒ごとに行なうことが出来るようにする。
 10)モータ停止位置は800としてあるあるが,変更できるようにしキーボードから
   どのような値(だいたい±10000の範囲)でも設定できるようにしなさい。

(2)次の仕様のプログラムを作りなさい。
 1)カウンタ値0の位置からモータを駆動し,0.005秒ごとに,カウンタ値が20ず
   つ増加するようにしなさい。
  (0.000秒:0 0.005秒:20 0.010秒:40 0.015秒:60 0.020秒:80
    .....)
 2)モータ駆動直前に角度センサのカウンタをクリアする。
 3)予定した時刻に予定した位置を正確に通過しなくてもよいが,できるだけこの
   ような軌跡になるようにしなさい。
 4)モータ起動時および起動後0.005秒ごとに,その時の時刻,PWM値,角度目標値,
   角度,角度差分を表示する。
  (この表示はキャプチャして,Excelでグラフ化し,これも提出すること)
 5)角度はその時刻のカウンタ値,角度差分は0.005秒間のカウンタ値の差分とする。
 6)PWM値,角度,角度差分の表示はモータ起動1秒後までとする。
 7)角度,角度差分の表示は割り込み関数内で行なってはいけない。
  (割り込み関数は出来るだけ作業を短時間に終わりたいからである)
 8)PWM値の更新は0.005秒ごとに行なうことが出来るようにする。
 9)モータは起動後1秒後に停止することにし,この作業は何回でも実行できる
   ようにする。
 10)カウンタ値の増分は20とされているが,変更できるようにし,キーボード
   から-30〜30程度を入力して,
   任意の値に出来るようにしておくこと


練習問題11D

(1)次の仕様のプログラムを作りなさい。
 1)カウンタ値0の位置からモータを駆動し,カウンタ値が800の位置でモータを止める。
 2)モータ駆動直前に角度センサのカウンタをクリアする。
 3)正確に800の位置に止められなくてもよいが,できるだけ800に近い位置に止める。
 4)この作業は何回でも繰返し出来るようにしなさい。
 5)モータ起動時および起動後0.01秒ごとに,その時の時刻,PWM値,角度,角度差
   分を表示する。
  (この表示はキャプチャして,Excelでグラフ化し,これも提出すること)
 6)角度はその時刻のカウンタ値,角度差分は0.005秒間のカウンタ値の差分とする。
 7)時刻,PWM値,角度,角度差分の表示はモータ起動1秒後までとする。
 8)角度,角度差分の表示は割り込み関数内で行なってはいけない。
  (割り込み関数は出来るだけ作業を短時間に終わりたいからである)
 9)PWM値の更新は0.0005秒ごとに行なうことが出来るようにする。
 10)モータ停止位置は800としてあるあるが,変更できるようにしキーボードから
   どのような値(だいたい±10000の範囲)でも設定できるようにしなさい。

(2)次の仕様のプログラムを作りなさい。
 1)カウンタ値0の位置からモータを駆動し,0.01秒ごとに,カウンタ値が20ず
   つなめらかに増加するようにしなさい。
  (0.00秒:0 0.01秒:20 0.02秒:40 0.03秒:60 0.04秒:80
    .....)
 2)モータ駆動直前に角度センサのカウンタをクリアする。
 3)予定した時刻に予定した位置を正確に通過しなくてもよいが,できるだけこの
   ような軌跡になるようにしなさい。
 4)モータ起動時および起動後0.01秒ごとに,その時の時刻,PWM値,角度目標値,
   角度,角度差分を表示する。
  (この表示はキャプチャして,Excelでグラフ化し,これも提出すること)
 5)角度はその時刻のカウンタ値,角度差分は0.005秒間のカウンタ値の差分とする。
 6)PWM値,角度,角度差分の表示はモータ起動1秒後までとする。
 7)角度,角度差分の表示は割り込み関数内で行なってはいけない。
  (割り込み関数は出来るだけ作業を短時間に終わりたいからである)
 8)PWM値の更新は0.0005秒ごとに行なうことが出来るようにする。
 9)モータは起動後1秒後に停止することにし,この作業は何回でも実行できる
   ようにする。
 10)カウンタ値の増分は20とされているが,変更できるようにし,キーボード
   から-30〜30程度を入力して,

(3)次の仕様のプログラムを作りなさい。  実行例(ヒントもあり)
 1)時刻-変位(カウンタ値)グラフが台形になることをめざした制御を行ないなさい。
 2)カウンタ値0の位置からモータを駆動し,はじめの1秒間は等速運動でカウンタ値2000まで動作します。次の1秒間はカウンタ値2000を保ちます。その次の1秒間はカウンタ値0まで等速運動で戻ります。最後の1秒間はカウンタ値0を保ちます。(全4秒間の制御とします)
 3)正確な台形グラフどおりにならなくても良いが,できるだけ台形動作を行なうようにしなさい
 4)モータ起動時および起動後0.01秒ごとに,その時の時刻,PWM値,角度目標値,
   角度,角度差分を表示する。
  (この表示はキャプチャして,Excelでグラフ化し,これも提出すること)
 5)角度はその時刻のカウンタ値,角度差分は0.005秒間のカウンタ値の差分とする。
 6)PWM値,角度,角度差分の表示はモータ起動4秒後までとする。
 7)角度,角度差分の表示は割り込み関数内で行なってはいけない。
  (割り込み関数は出来るだけ作業を短時間に終わりたいからである)
 8)PWM値の更新は0.0005秒ごとに行なうことが出来るようにする。
 9)この作業は何回でも実行できるようにする。


4.12 PSDプログラム

PSD素子の上方20cm程度の位置に手をかざすと距離計が反応する。

図13 赤外線距離計PSD(SHARP GP2D12)

リスト 12.1
赤外線距離計PSD(Position Sensitive Detector)プログラム

/****************************************
赤外線距離計PSD(Position Sensitive Detector) (AN1)
****************************************/

#include "3048f.h"
#include "h8_3048.h"

/***************************************
ADコンバータ (単一モード)

void initADC(void)
 ADC初期化ADC単一モード初期化(インタラプト禁止,変換時間=134ステート)

unsigned int getADC(unsigned char ch)
 AD変換結果の取得
 この関数を呼び出した時にAD変換命令が作られ,
 変換終了まで待ち,AD変換値を取得する。
 chは0,1,2,3,4,5,6,7に対応している。

--------------------
void initADC0(void)
 ADC初期化ADC単一モード初期化(ch0のみに特化したバージョン)

unsigned int getADC0(void)
 AD変換結果の取得
 この関数を呼び出した時にAD変換命令が作られ,
 変換終了まで待ち,AD変換値を取得する。
 ch0のみに特化したバージョン
--------------------
void initADC1(void)
 ADC初期化ADC単一モード初期化(ch1のみに特化したバージョン)

unsigned int getADC1(void)
 AD変換結果の取得
 この関数を呼び出した時にAD変換命令が作られ,
 変換終了まで待ち,AD変換値を取得する。
 ch1のみに特化したバージョン

出力電圧    data
  0V  →      0
  5V  →   1023

****************************************/

void initADC(void)
{
    AD.CSR.BIT.ADF= 0;   /*エンドフラグをクリア*/
    AD.CSR.BIT.ADIE=0;   /*インタラプト禁止*/
    AD.CSR.BIT.ADST=0;   /*スタート停止*/
    AD.CSR.BIT.SCAN=0;   /*単一モード*/
    AD.CSR.BIT.CKS= 1;   /*変換時間=134ステート*/
}

unsigned int getADC(unsigned char ch)
{
    AD.CSR.BIT.CH=  ch;         /*チャネル設定 */
    AD.CSR.BIT.ADST = 1;        /*AD変換スタート*/
    while(AD.CSR.BIT.ADF == 0); /*変換終了まで待つ*/ 
    AD.CSR.BIT.ADF= 0;          /*エンドフラグをクリア*/
                                /* ADSTは自動的に0になっている*/
    ch&=3;
    return *(&AD.DRA+ch)>>6;
}

void initADC0(void)
{
    AD.CSR.BIT.ADF= 0;   /*エンドフラグをクリア*/
    AD.CSR.BIT.ADIE=0;   /*インタラプト禁止*/
    AD.CSR.BIT.ADST=0;   /*スタート停止*/
    AD.CSR.BIT.SCAN=0;   /*単一モード*/
    AD.CSR.BIT.CKS= 1;   /*変換時間=134ステート*/
    AD.CSR.BIT.CH=  0;         /*チャネル設定 */
}

unsigned int getADC0(void)
{
    AD.CSR.BIT.ADST = 1;        /*AD変換スタート*/
    while(AD.CSR.BIT.ADF == 0); /*変換終了まで待つ*/ 
    AD.CSR.BIT.ADF= 0;          /*エンドフラグをクリア*/
                                /* ADSTは自動的に0になっている*/
    return AD.DRA>>6;
}

void initADC1(void)
{
    AD.CSR.BIT.ADF= 0;   /*エンドフラグをクリア*/
    AD.CSR.BIT.ADIE=0;   /*インタラプト禁止*/
    AD.CSR.BIT.ADST=0;   /*スタート停止*/
    AD.CSR.BIT.SCAN=0;   /*単一モード*/
    AD.CSR.BIT.CKS= 1;   /*変換時間=134ステート*/
    AD.CSR.BIT.CH=  1;         /*チャネル設定 */
}

unsigned int getADC1(void)
{
    AD.CSR.BIT.ADST = 1;        /*AD変換スタート*/
    while(AD.CSR.BIT.ADF == 0); /*変換終了まで待つ*/ 
    AD.CSR.BIT.ADF= 0;          /*エンドフラグをクリア*/
                                /* ADSTは自動的に0になっている*/
    return AD.DRB>>6;
}

/*何もしないで指定された時間[msec]たつと戻る関数*/
void msecwait(int msec)
{
    int i;
    long int j;
    for (i=0;i<msec;i++) {
        for (j=0;j<33300;j++);    /*33300は実測によって求めた値*/
    }
}

main()
{
    unsigned int y;
    initSCI1();
    initADC1();
    SCI1_printf("       **   Position Sensitive Detector   **\n");
    while (1) {
        y=getADC1();
        SCI1_printf("PSD ADC:%4d (ADC/4:%3d) \r",y,y>>2);
        msecwait(200);
    }
}


 
 参考1 H8ピン配置

H8-CN.JPG - 98,702BYTES

AKI-H8付属のコネクタ番号表


参考2 h8_3048.h

h8_3048.h

/****************************************************************
h8_3048.h
Copyright (c) Kosaka Lab CS TNCT

このインクルードファイルは小坂研究室の代々の研究生が開発した
有用な関数群を改良して小坂がまとめたものである。
28 Jun 2006 h8-3048.h  小坂 chkgetSCI1のタイミング修正
 4 Dec 2003 h8-3048.h  小坂 printf更新,initLed更新,initDDR削除
08 Oct 2003 h8-3048.h  小坂 stopTimer追加,getIntSCI1でBS使用可
 6 Jan 2003 h8_3048.h  小坂 getIntSCIバックスペイスに対応。
17 Apr 2002 h8-01.h  小坂 %uの使い方をansiにあわせた。
14 Dec 2001 h8-01.h  小坂,越智
15 Jly 2000 h8-00.h  小坂,藤原
22 Dec 1999 h8-99.h  小坂,高沢
29 Oct 1999 h8-99.h  小坂
05 Feb 1999 lib.h    笠井

【1】ポートの入出力管理
void initDDR(void)
 write only register DDR設定用変数の初期化

【2】SCI ch1 関係
void initSCI1()
 SCI-ch1の初期化 38400baud, Async, 8bit , NoParity, stop1

short int getCharSCI1()
 SCI-ch1から1byte入力コード。エラーがあると-2が戻る。
short int chkgetCharSCI1()
 SCI-ch1を検査し,受信データがあれば1byte入力コード。なければ-1が,失敗すると-2が戻る。
short int getIntSCI1(char prompt[])
 SCI-ch1からプロンプト付で,short intの値を受け取る。
 正負の10進数または16進数を受け付ける。16進数は0xで始まる

void putCharSCI1(char c)
 SCI-ch1に1バイト出力する。
void putStringSCI1(char *str)
 SCI-ch1に文字列を出力する。
void SCI1_printf(char *format,...)
  関数printfのSCI版
  軽量化のためエラー処理はないので桁数指定の場合は注意
  対応書式
  %d   : [int] integer with sign. '%d','%4d','%-4d', and '%04d' are available
  %ld  : explicit [long int]  '%ld','%9ld','%-9ld', and '%09ld' are available
  %u   : [unsigbed int] unsigned integer.
            '%u','%4u','%-4u', and '%04u' are available
  %lu  : explicit [unsigned long int]
            '%lu','%9lu','%-9lu', and '%09lu' are available
  %x   : [unsigned int] in Hex  '%x','%4x','%-4x', and '%04x' are available
  %lx  : explicit [unsigned long int] in Hex 
            '%lx','%8lx','%-8lx', and '%08lx' are available
  %o   : [unsigned int] in Oct  '%o','%4o','%-4o', and '%04o' are available
  %lo  : explicit [unsigned long int] in Oct 
            '%lo','%8lo','%-8lo', and '%08lo' are available
  %b   : [unsigned int] in Bin  '%b','%8b','%-8b', and '%08b' are available
  %lb  : explicit [unsigned long int] in Bin 
            '%lb','%8lb','%-8lb', and '%08lb' are available
  %c   : char
  %s   : string %20s %-20s are available

【3】AKI-H8マザーボード関係
void initLed()
 LEDの初期化
void turnOnLed(short int number)
 LEDの点灯 numberはLED番号で0または1を指定する
void turnOffLed(short int number)
 LEDの消灯 numberはLED番号で0または1を指定する

void initPushSW(void)
 押しボタンスイッチの初期化
short int getPushSW(void)
 押しボタンスイッチの取得 ただしポートを読み込み,ビット反転のみ。
 押しボタンスイッチの状況は第4-第7ビットに現れる。
 これはマクロ定義で実現されている
short int checkPushSW(short int number)
 push sw 0,1,2,3の状態を調べる number:0,1,2,or 3
 押されていたら1、そうでなかったら0を返す

void init8BitSW(void)
 8ビットスイッチの初期化
short int get8BitSW(void)
 8ビットスイッチの取得 ただしポートを読み込み,ビット反転のみ。
 8ビットスイッチの状況は第0-第7ビットに現れる。
 これはマクロ定義で実現されている
short int check8BitSW(short int number)
 8bitsw 0,1,2,3,4,5,6,7の状態を調べる number:0,1,2,3,4,5,6,or 7
 ONなら1、そうでなかったら0を返す

【4】タイミング割り込み
void initTimer1Int(unsigned short int period)
 ITU1による割り込みタイマーの設定
 割り込み間隔は引数peiodで単位はμsecである
 値は32767以下でなければならない。32.767msecまで設定可能
void startTimer1(void)
 Timer CH1 スタート
 これはマクロ定義で実現されている

void initTimer01Int(unsigned short int period)
 ITU0とITU1による割り込みタイマーの設定
 割り込み間隔は引数peiodで単位はmsecである
 値は65535以下でなければならない。65.535secまで設定可能
 ただしポートPAの第3ビットが使用できなくなるので注意
void startTimer01(void)
 Timer CH0 CH1 同時スタート
 これはマクロ定義で実現されている

****************************************************************/

#include<stdarg.h>

unsigned char P1DDR=0,P2DDR=0,P3DDR=0,P4DDR=0,P5DDR=0;
unsigned char  P6DDR=0,P7DDR=0,P8DDR=0,P9DDR=0,PADDR=0,PBDDR=0;

extern void E_INT();
extern void D_INT();

/*void initDDR(void)
{
    P1DDR=P2DDR=P3DDR=P4DDR=P5DDR=P6DDR=P7DDR=P8DDR=P9DDR=PADDR=PBDDR=0;
}
*/
/*以前のバージョンとの互換性のため*/
#define initDDR()

/*SCI関係の基本部分は笠井君(1998年度)藤原君(2000)の開発です*/
/* ------------------------------------------------- */
/* SCI1 INITIALIZATION fixed baud at 38400           */
/* ------------------------------------------------- */
void initSCI1()
{
    short int i;
    /*unsigned char dummy;*/
    SCI1.SCR.BYTE = 0;       /* clear all flags */
                      /* 2400-38400baud are available at n=0(cks1=0,cks2=0) */
    SCI1.SMR.BYTE = 0;       /* Async, 8bit , NoParity, stop1, 1/1 */
    SCI1.BRR = 12;          /* 38400baud (CPU=16MHz) */
    for(i=0;i<1000;i++);      /* wait more than 1bit time */
    SCI1.SCR.BYTE = 0x30;    /* scr = 0011 0000 (TE=1,RE=1) */
    /*dummy = SCI1.SSR.BYTE;*/   /* read dummy             ????*/
    /*SCI1.SSR.BYTE = 0x80;*/  /* clear error flag (TDRE = 1)     ????*/
    return;
}

/* ------------------------------------------------- */
/* GET BYTE FROM SCI1 */
/* ------------------------------------------------- */
short int getCharSCI1()
/* return value 0x00-0xFF:received data */
/*              -2(0xFFFE):error */
{
    short int flags,recdata;
    do {
        flags = SCI1.SSR.BYTE;
        if (flags&0x38) {/* error */
            SCI1.SSR.BIT.RDRF = 0;
            SCI1.SSR.BIT.ORER = 0;
            SCI1.SSR.BIT.FER = 0;
            SCI1.SSR.BIT.PER = 0;
            return -2;
        }
        if (flags&0x40) {/* normally received one data */
            SCI1.SSR.BIT.RDRF = 0;
            recdata=SCI1.RDR;
            return recdata;
        }
    } while (1);
}

/* ------------------------------------------------- */
/* CHECK SCI BUFFER AND GET DATA */
/* ------------------------------------------------- */
short int chkgetCharSCI1()
/* return value -1(0xFFFF):no received data  */
/*              0x00-0xFF:received data */
/*              -2(0xFFFE):error */
{
    short int flags,recdata;
    flags = SCI1.SSR.BYTE;
    if (flags&0x38) {/* error */
        SCI1.SSR.BIT.RDRF = 0;
        SCI1.SSR.BIT.ORER = 0;
        SCI1.SSR.BIT.FER = 0;
        SCI1.SSR.BIT.PER = 0;
        return -2;
    }
    if (flags&0x40) {/* normally received one data */
        recdata=SCI1.RDR;
        SCI1.SSR.BIT.RDRF = 0;
        return recdata;
    } else {
        return -1;
    }
}

void putStringSCI1(char *str);

/*SCI1より文字列入力[return]が終端だが,'\n'は取得されない*/
/*^Hでバックスペイス*/
int getStringSCI1(char *buff,int max)
{
    int i,ch;
    for (i=0;i<max-1;i++) {
        ch=getCharSCI1(); /*1文字取得*/
        *buff=(char)ch; /*1文字取得*/
        if (*buff=='\r'||ch<0) {
            *buff=0;
            return i+1;
        }
        if (*buff==0x8) {
            buff-=2;
            i-=2;
        }
        if (*buff!='\n') buff++;
        else i--;
    }
    *buff=0;
    return i+1;
}

/*SCI1へプロンプトを表示して,SCI1より整数値を入力*/
short int getIntSCI1(char prompt[])
/*getting integer from serial port*/
/* format 123[ret] */
/*        -123[ret] */
/*        0x1a[ret] */
/*        -0x100[ret] */
{
    short int x=0,y,m=0,n=0,v=0,i=0;
    char buff[16];
    putStringSCI1(prompt);
    getStringSCI1(buff,16);
    y=buff[i];
    while(y!=0){
        if(y=='-') m=1;
        if('a'<=y&&y<='z') y=y-'a'+'A';
        if(y=='0') n=1;

        if(v==1){
            if('0'<=y&&y<='9'){
                y=y-'0';
            }
            else if('A'<=y&&y<='F'){
                y=y-'A'+10;
            }
            x=16*x+y;
        }

        if(n==1&&y=='X'){
            v=1;
        }
               
        if(v==0&&'0'<=y&&y<='9'){
            y=y-'0';
            x=10*x+y;
        }

        y=buff[++i];
    }
    if(m==1) x=-x;
    return x;
}

/* ------------------------------------------------- */
/* PUT BYTE TO SCI1 */
/* ------------------------------------------------- */
void putCharSCI1(char c)
{
    unsigned char tmp;
    if (c=='\n') putCharSCI1('\r');
    do{
        tmp = SCI1.SSR.BYTE;
    } while((tmp & 0x80)==0);
    SCI1.TDR = c;
    SCI1.SSR.BIT.TDRE = 0;
    return;
}

void putStringSCI1(char *str)
{
    while(*str){
        putCharSCI1(*str);
        str++;
    }
}

const char hexstring[]="0123456789abcdef0123456789ABCDEF";
#define MAXDIGIT 34
void SCI1_printf(char *format,...)
{
    va_list arg_ptr;
    char buf[MAXDIGIT];
    unsigned char flag=0;  /*%d:bit2 l:bit1 %:bit0 */
    unsigned char digit=0; /* 桁数 */
    unsigned char minus=0;
    char fill=' ',format1=' ';
    unsigned char radix=10; /*N進基数*/
    char sign=' ';
    char *ptr=buf; /*出力文字ポインタ*/
    unsigned char cntr=0; /*出力文字数カウンタ*/
    unsigned char shift=0; /*16進シフト 0 or 6*/
    unsigned char i;
    unsigned long int value=0;
    va_start(arg_ptr,format);
    while (*format) {
        format1=*format;
        if (flag==0) {
            if (format1=='%') {
                flag=1;
                digit=0;
                fill=' ';
                minus=0;
                radix=0;
                ptr=&buf[MAXDIGIT-1];
                *ptr--='\0';
                cntr=0;
                shift=0;
                sign='+';
            } else {
                putCharSCI1(format1);
            }
        } else {
            if (format1=='l') {
                flag|=2;
            } else if ('0'<=(format1)&&(format1)<='9') {
                if (digit==0 && format1=='0') {
                    fill='0';
                } else {
                    digit=digit*10+((format1)-'0');
                    if (MAXDIGIT-2<digit) digit=MAXDIGIT-2;
                }
            } else if (format1=='-') {
                minus=1;
            } else if (format1=='d') {
                flag|=4;
                radix=10;
            } else if (format1=='u') {
                radix=10;
            } else if (format1=='x') {
                radix=16;
            } else if (format1=='X') {
                radix=16;shift=16;
            } else if (format1=='o') {
                radix=8;
            } else if (format1=='b') {
                radix=2;
            } else if (format1=='p') {
                radix=16;shift=16;digit=8;fill='0';flag|=2;
            } else if (format1=='c') {
                putCharSCI1((unsigned char)(va_arg(arg_ptr,int)));
                flag=0;
            } else if (format1=='s') {
                if (digit) {
                    cntr=0;ptr=va_arg(arg_ptr,char *);
                    while (ptr[cntr]) cntr++; /*cntrは文字数*/
                    if (!minus) for (i=cntr;i<digit;i++) putCharSCI1(' ');
                    putStringSCI1(ptr);
                    if (minus) for (i=cntr;i<digit;i++) putCharSCI1(' ');
                } else {
                    putStringSCI1(va_arg(arg_ptr,char *));
                }
                flag=0;
            } else {
                putCharSCI1(format1);
                flag=0;
            }
            if (radix) {
                switch (flag&6) {
                case 0: /* unsig int */
                    value=(unsigned int)va_arg(arg_ptr,int);
                    break;
                case 2: /* unsig long int */
                    value=va_arg(arg_ptr,long int);
                    break;
                case 4: /* sig int */
                    value=(long int)va_arg(arg_ptr,int);
                    if ((long int)value<0) {
                        value=-(long int)value;
                        sign='-';
                    }
                    break;
                case 6: /* sig long int */
                    value=va_arg(arg_ptr,long int);
                    if ((long int)value<0) {
                        value=-(long int)value;
                        sign='-';
                    }
                    break;
                default:
                    break;
                }
                while (value) {
                    *ptr--=hexstring[value%radix+shift];
                    cntr++;
                    value/=radix;
                }
                if (cntr==0) {
                    *ptr--='0';
                    cntr++;
                }
                if (fill==' ') {
                    if (sign=='-') {
                        *ptr--='-';
                        cntr++;
                    }
                    if (!minus) for (i=cntr;i<digit;i++) putCharSCI1(' ');
                    putStringSCI1(++ptr);
                    if (minus) for (i=cntr;i<digit;i++) putCharSCI1(' ');
                } else {
                    for (;cntr<digit-1;cntr++) *ptr--='0';
                    if (sign!='-'&&cntr<digit) *ptr--='0';
                    else if (sign=='-') *ptr--='-';
                    putStringSCI1(++ptr);
                }
                flag=0;
            }
        }
        format++;
    }
}

/* ------------------------------------------------- */
/* LED INITIALIZATION */
/* ------------------------------------------------- */
/**********************************************************
LED 0:P5-0
LED 1:P5-1
**********************************************************/
void initLed()
{
    P5DDR |=  0x3;
    P5.DDR = P5DDR;
}

/* ------------------------------------------------- */
/* LET LED ON */
/* ------------------------------------------------- */
/*numberは0または1*/
void turnOnLed(short int number)

    static unsigned char mask[]={1,2};
    P5.DR.BYTE |=mask[number];
}

/* ------------------------------------------------- */
/* LET LED OFF */
/* ------------------------------------------------- */
/*numberは0または1*/
void turnOffLed(short int number)
{
    static const unsigned char mask[]={0xfe,0xfd};
    P5.DR.BYTE &=mask[number];
}

/* ------------------------------------------------- */
/* PUSH SW INITIALIZATION */
/* ------------------------------------------------- */
/**********************************************************
押しボタンスイッチS0:P4-4
押しボタンスイッチS1:P4-5
押しボタンスイッチS2:P4-6
押しボタンスイッチS3:P4-7
**********************************************************/
void initPushSW(void)
{
    P4DDR &= 0xf; /*P4-4,5,6,7は入力*/
    P4.DDR=P4DDR;
    P4.PCR.BYTE|=0xf0; /*P4-4,5,6,7はプルアップ */
}

/* ------------------------------------------------- */
/* GET PUSH SW  */
/* ------------------------------------------------- */
/*push swの状態をそのまま返す
short int getPushSW(void)
{
    return (((unsigned char)(~P4.DR.BYTE))&0xf0);
}
*/
#define getPushSW() (((unsigned char)(~P4.DR.BYTE))&0xf0)

short int checkPushSW(short int number)
/*push sw 0,1,2,3の状態を調べる number:0,1,2,or 3*/
/*押されていたら1、そうでなかったら0を返す*/
{
    short int ret;
    static const unsigned char mask[]={0x10,0x20,0x40,0x80};
    if (P4.DR.BYTE&mask[number]) ret=0;
    else ret=1;
    return ret;
}

/* ------------------------------------------------- */
/* PUSH 8 BIT SW INITIALIZATION */
/* ------------------------------------------------- */
void init8BitSW(void)
{
    P2DDR &=  0x00;/*8bitSWのポートを入力に設定*/
    P2.DDR = P2DDR;
    P2.PCR.BYTE = 0xff;/*8bitSWのプルアップ設定*/
}

/*8bitswの状態をそのまま返す
short int get8BitSW(void)
{
    return (unsigned char)(~P2.DR.BYTE);
}
*/
#define get8BitSW() (unsigned char)(~P2.DR.BYTE)

short int check8BitSW(short int number)
/*8bitsw 0,1,2,3,4,5,6,7の状態を調べる number:0,1,2,3,4,5,6,or 7*/
/*ONなら1、そうでなかったら0を返す*/
{
    short int ret;
    static const unsigned char mask[]={1,2,4,8,0x10,0x20,0x40,0x80};
    if (P2.DR.BYTE&mask[number]) ret=0;
    else ret=1;
    return ret;
}

/*タイマ割り込みは笠井君(1998),越智君(2001)による開発です*/
/* ------------------------------------------------- */
/* TIMER INITIALIZATION */
/* ------------------------------------------------- */
void initTimer1Int(unsigned short int period)
/*ITU1による割り込みタイマーの設定(越智君2001による)*/
/*割り込み間隔は引数peiodで単位はμsecである*/
/*値は32767以下でなければならない*/
/*32.767msecまで*/
{
    ITU1.TCR.BIT.CCLR=1;  /*GRAのコンペアマッチでTCNTをクリア*/
    ITU1.TCR.BIT.CKEG=0;  /*立ち上がりエッジでカウント*/
    ITU1.TCR.BIT.TPSC=3;  /*内部クロックφ/8でカウント*/
    ITU1.GRA=2*period-1;  /*割り込みの周期をperiod[μs]に指定*/
    ITU1.TIER.BIT.IMIEA=1; /*TCNT=GRAとなったときの割り込み要求を許可*/
    ITU1.TIER.BIT.OVIE=0;  /*オーバー・アンダーフロー発生時の割り込みを禁止*/
    ITU1.TIER.BIT.IMIEB=0;  /*TCNT=GRBとなったときの割り込みを禁止*/
}

void initTimer01Int(unsigned short int period)
/*ITU0とITU1による割り込みタイマーの設定(笠井君(1998)による)*/
/*割り込み間隔は引数peiodで単位はmsecである*/
/*値は65535以下でなければならない*/
/*65.535secまで*/
/*ただしポートPAの第3ビットが使用できなくなるので注意*/
{
    ITU0.TCR.BYTE = 0xc3;   /* タイマー CH0 GRBでクリア、内部1/8クロック */
    ITU0.TIOR.BYTE = 0xb8;  /* タイマー CH0 GRBのコンペアマッチでトグル出力 */
    ITU0.GRB = 2000-1;        /* タイマー CH0 ((16/8)MHz)/1000Hz=2000 */
   
    ITU1.TCR.BYTE = 0xb7;   /* タイマー CH1 GRAでクリア、TCLKDをカウントする */
    ITU1.TIOR.BYTE = 0x8a;  /* タイマー CH1 GRAのコンペアマッチ出力 */
    ITU1.GRA = period-1;      /* タイマー CH1 1000 = 1SEC */
    ITU1.TIER.BYTE = 0xf9;  /* タイマー CH1 GRAで割り込みする */
}

/* ------------------------------------------------- */
/* TIMER START */
/* ------------------------------------------------- */
/*
Timer CH0 CH1 同時スタート
void startTimer01(void)
{
    ITU.TSTR.BYTE |= 0x03;
}
Timer CH1 スタート
void startTimer1(void)
{
    ITU.TSTR.BYTE |= 0x02;
}

Timer CH0 CH1 同時ストップ
void stopTimer01(void)
{
    ITU.TSTR.BYTE &= ~0x03;
}
Timer CH1 ストップ
void stopTimer1(void)
{
    ITU.TSTR.BYTE &= ~0x02;
}
*/
#define startTimer01() (ITU.TSTR.BYTE |= 0x03) /* Timer CH0 CH1 同時スタート */
#define startTimer1()  (ITU.TSTR.BYTE |= 0x02) /* Timer CH1 スタート */
#define stopTimer01()  (ITU.TSTR.BYTE &= ~0x03) /* Timer CH0 CH1 同時ストップ */
#define stopTimer1()   (ITU.TSTR.BYTE &= ~0x02) /* Timer CH1 ストップ */