UMEHOSHI ITA TOP PAGE    COMPUTER SHIEN LAB

[UMEHOSHI ITA]の制御で使っているIC「PIC32MX270F256B-I/SO」のフラッシュメモリには、テスト用プログラムが書き込まれいています。
以降では、このプログラムを「テスト・ウメ・フラッシュ」と呼ぶことにして解説します。
また、「テスト・ウメ・フラッシュ」を利用したユーザー用のプログラムを 「ウメ・エディットプログラム」と呼ぶことにします。
「ウメ・エディットプログラム」の開発では「umehoshiEditツール」が必要で、 その取得や最初の操作情報は、こちらを参照してください。
(「PICKit3などの書き込みツール」をお持ちの方で、「テスト・ウメ・フラッシュ」を利用しないで、 「MPLAB X IDE」の開発環境ですべてをプログラミングする場合の情報ではありません。)
「テスト・ウメ・フラッシュ」をどのように利用して、「ウメ・エディットプログラム」を 作るかの解説で、「umehoshiEditツール」の使用例を示しています。
各サンプルは、このWebページ上でドラック&コピーして、貼り付けしてご利用ください。

各種確認プログラム左記に必要な部品の追加例

USBで接続されるホストにメッセージ(文字列)を送信する。

とくに必要ありません。
(D1のLEDは、あるとよい)

モータ制御、PWM (Timer2利用)

PWM対応の部品追加例

ADC(A/Dコンバータ)を使う(Timer3利用)

ADC 対応の部品追加例

BEEP(ブザー音で、デフォルトのCORE Timer、Timer1を利用)

BEEP SWITCH 対応の部品追加例

[UMEHOSHI ITA]単体で動作させる

Reset SW, Type-A, CN2 部品追加例

赤外線制御

U20,D4,D5,NPN, D3 部品追加例

UART を介して、Bluetoothで制御

CN11,CN-12 部品追加例

UART を介して、ESP32-WROOM-32DをBASIC制御

U19 部品追加例

UART を介して、RN4020(BLE)で制御

U17にRN4020の部品を追加する例

[UMEHOSHI ITA]を赤外線で制御する

[UMEHOSHI ITA]で動作させる時に必要な部品の追加です。

目標の仕様を説明します。
プログラムをロードします。(赤外線リモコンの学習モードへの状態変数設定など、各種の初期化が行われます。)
最初のプログラムスタート([80005000]番地より実行)は、赤外線リモコンの学習モードです。
この状態で、 家にあるテレビのリモコンなどを、取り付けた赤外線受光IC(U20)に向けて、電源オンの操作をします。
この受信で得られた赤外線のパターンを[UMEHOSHI ITA]で記憶します。
受光で得られた信号パターンをうまく記憶できた時は、それを知らせるためにD1のLED(黄緑)を点灯させます。

この状態で、再びプログラムスタート([80005000]番地より実行)させます。
こんどは、上記で記憶したパターンで D4,D5 の赤外線LEDを発光させてリモコン対象を操作します。
これで、リモコン対象のテレビの電源がオンできれば成功ということです。
これ以降は[UMEHOSHI ITA]への電源供給を切るまで、 プログラムスタート([80005000]番地より実行)で 同じパターンの赤外線LEDの発光(リモコン操作)を行います。


以上のプログラム作るため、一般的な赤外線リモコンの動作を理解する必要があります。
いくつのパターン(NEC/家製協/SONYフォーマット)があるようですが、 NECフォーマットをベースに以下で考えてみます。
まず、デジタルとしての 1や 0の信号は 38KHzで1/3dutyのサブキャリアで伝達されます。 次のイメージです。

上記のキャリアが存在している時間幅はT(変調単位 = 562μs)と呼ばれ、0はの幅はT×2で、1はの幅はT×4になっています。
(上記の 1は、キャリアありのTと、キャリアなしのT×3で、1の幅全体はT×4になっていますが、 SONYフォーマットでは異なる比率です。
また、TはNECフォーマットで 562μs、家製協(AEHA)フォーマットで 350〜500μs、SONYフォーマットで600μsで違いがあるようです。)
上記のようなビット伝達は、下記の破線で示す「frame」と呼ばれる入れ物に入れたイメージで伝達されます。
「frame」の先頭部は、上記のように「Leader」とよばれるキャリアありの情報で同期をとります。
「Leader」のキャリアありの時間幅は、NECフォーマットで16T、 家製協(AEHA)フォーマットで8T、SONYフォーマットで4Tと、異なります。
またキー操作でONの間だけ、「frame」が複数でるものや、[Rpeat]と呼ばれるパターンがでるものなどがあります。

よって、ある一定期間キャリアが存在しなければ、キー操作をOFFと判断するのがよいでしょう。

なお、赤外線受光IC(OSRB38C9AA)の出力は、サブキャリアが存在すると判定した期間だけLowになります。
つまり、サブキャリアがない時は、Hiになります。これを前提にプログラミングする必要があります。

この仕様を実現するプログラムの作成

「サブキャリア: fsc = 38kHz, 1/3duty」は、タイマ割込み内で、D4、D5の赤外線LEDのON/OFFすることで作ります。
そこで、約38KHz周期/3のdtの周期を目標にしてタイマーを使うことにします。
この周期でリモコンの赤外線の受信情報を記憶し、この周期で再生するプログラムにするわけです。
上記波形のキャリア有りや無しに変化するまでの期間を、この周期のカウント値で記憶します。

dtを 1/38KHz/3 とすると、サブキャリアの変調は、
dt秒の間ONした後、(dt*2)u秒の間OFFする』を繰り返すことで 赤外線LEDのキャリアを作ります。(発光の点滅です)
(この1/3dutyの点滅幅比率は、各フォーマット共通のようです)

このクロックは、Timer4で次のように作ります。
周辺モジュール用クロックが 40e6Hzなので、
T4CONbits.TCKPS = 0;// タイマ入力クロック0〜7 [1:1]プリスケール値(b6-b4)にして、
PR4=351にすると、約38KHz周期/3のdtが得られます。
これは「(1/38e3/3)/(1/40e6)=350.8771929824562より算出した値です」
このPR4=351の場合、Timer4の割込みは (1/40e6*351) = 8.775e-06 秒間隔になります。
受信ではこの間隔でサブキャリアが存在するタイミングを記録し、
送信ではこの間隔でサブキャリアが存在するタイミング中のON/OFF制御でキャリアの波形を生成します。 このTimer4の割込み初期化は次のようになります。

void init_timer4() //割り込みの初期化もカスタマイズする関数
{
	T4CON =0x00000000;//typeB,16bit, [1:1]プリスケール
	TMR4=0x00000000; //16bitタイマの設定値(レジスタがカウントアップ)
	PR4=351; //	8.775e-06秒間隔の割込み(1/38e3/3)
	IPC4bits.T4IP = 6; // Set priority level = 6(2番に大きな優先度)
	IPC4bits.T4IS = 0;// Set sub-priority level = 3(最大値)
	IFS0bits.T4IF = 0;// Clear the timer interrupt status flag
	IEC0bits.T4IE = 1;// Timer4 Enable(割込み許可).
}
グローバル的な変数 frame_status の状態で、タイマ割込み関数( timer4() )内で、 受信の記録処理「rec_infrared() 」かまたは、記録より赤外線の再生送信処理「snd_infrared()」の分岐を行います。


リモコン受信でタイミングを記憶する(rec_infrared())

この中で、リモコンからの受光で、そのパターンを学習するわけですが、 それは、上記で示した 「Key ON」してから「Key OFF」までの 「frame」を含めたキャリアの変化を記憶します。
具体的には、まず「frame」内の先頭にある「Leader」を検出して、記憶を開始します。

受光ICの出力がLowであればキャリアありと判断しますが、 「Leader」の判定は、ある一定時間(FRAME_START_COUNT_VALのカウント値)のLowが存在していたらそうであると判断するだけです。
そして 「Leader」のLowとHiを含め、ある一定時間のキャリアが無いHiが続く(FRAME_END_COUNT_VALのカウント値)と 判断されるまでのLowとHiの変化に達する割込み回数を記録します。
この記録値は、割込みごとでカウントするtiming_counterの情報です。
このカウントの記録は、プログラムのロードで初期化されない領域の _MEMO3[3] から記憶順次に_MEMO3[0x0EFF]までに記憶します。
なお、一つのキー操作で記憶した、_MEMO3配列への記憶数を、_MEMO3[0]に記録します。
_MEMO3配列はbyte要素で、この一つのカウント値の記憶を、サイズに応じて複数の要素を使って記憶する次の技法を使います。
 ・一つの要素に記憶できるデータを0〜127に制限し、最上位bitには特別な次の意味を持たせる。
 ・最上位bitが1であれば、その上位7ビットが次の要素に続くと決めて使う。
   0であればその要素の7ビットが最上位で次に続く要素がない。
これによって、記憶域を効率的使えます。0から127であれば1byte要素に記憶でき、2byteの連続要素であれば、27×27=16383、
3byteの連続要素であれば、27×27×27=2097152まで記憶できます。
この方法であれば257を記憶する場合、[0x81],[0x02]と連続要素に記憶されます。
[0x81]の最上位ビットが1なので、次の連続要素も使って記憶していることになり、[0x0200>>2]+[0x01]=[0x0101]を意味します。

以上を実現するために、_MEMO3への格納関数「store()」、_MEMOデータの参照関数「restore()」を定義しました。
これを使う割込み内から呼び出される受信関数「rec_infrared() 」と受信関連のグローバル変数を以下に示します。

#include <xc.h>
#include "common.h"

int frame_status = 0; 
  //0:startを待つ, 1:frame受信中(end判定も行う), 2: 送信準備完了, 3:送信, 4:Error.
int FRAME_START_COUNT_VAL = 273;//startの判定に必要な1この期間に相当するカウント値 .
int FRAME_END_COUNT_VAL = 14814;//endの判定に必要な0この期間に相当するカウント値 (約0.13秒) .
int idx_rec=3;//受信のタイミング記憶位置(最初のキャリアありの記録位置).
int rb5_on = 0;	// キャリアありで1、キャリア無しで0
int prev_rb5_on=0;// 上記の変化を、割込み時の状態を記憶する(前の状態).

int timing_counter= 0;

// _MEMO3 のidx位置へ、dataを可変長サイズで記憶し、次の記憶用インデックスを返す.
int store(int idx, int data)
{
	for(;;) {
		_MEMO3[idx++] = data;//カウント値の記録.
		data >>= 7;
		if(data != 0) _MEMO3[idx-1] |= 0x80;//次の記憶がある?
		else return idx;
	}
}

// _MEMO3 のidx位置にある可変長データを*dataに記憶し、次の記憶用インデックスを返す.
int restore(int idx, int *data)
{
	*data = 0;
	int shift7 = 0;
	for(;;){
		int temp = _MEMO3[idx++];

		*data += (temp & 0x7f) << shift7; 
		if( (temp & 0x080) == 0 ) return idx;
		shift7 += 7;
	}
}

void rec_infrared() // 赤外線受信 (_PTR_RAM_AREA3+3 番地から、タイミングを記憶)
{
	if( idx_rec >= 0x0F00) {// 予想記憶域を超えた場合のエラー
		_debug_hex4(15,15,1);
		frame_status = 4;
		return;
	}
	prev_rb5_on = rb5_on;
    	rb5_on = (PORTB & 0x80) == 0; // キャリアありで 1を記憶.
	if( frame_status == 0 ) { // startを待つ状態.
		if( rb5_on == 0) {
			timing_counter= 0;
			return;// フレーム開始タイミングカウンタクリア.
		}
		timing_counter++;
            if( timing_counter >= FRAME_START_COUNT_VAL ){
			// フレーム開始とされる期間のLowが続いた?.
			frame_status = 1; // frame受信始まりと判断.
			//_debug_hex4(1,1,1);
		}
	} else if( frame_status == 1 ){ // frameの受信中 end check.
		timing_counter++;
		if( prev_rb5_on == 0 && timing_counter >= FRAME_END_COUNT_VAL ){//フレーム終了のチェック.
			idx_rec=store(idx_rec,timing_counter);//カウント値の記録.
			store(0,idx_rec);//記録数の設定
			frame_status = 2; //送信準備完了
			_RB15 = 1; // LED D1(黄緑)をON:受信が終わったことを視覚的に知らせる。.
			rb5_on = prev_rb5_on=0;
			//_debug_hex4(2,2,1);
		}
		if( rb5_on == 0 && prev_rb5_on != rb5_on ) {// 立下りを待つ.
			idx_rec=store(idx_rec,timing_counter);//カウント値の記録.
			timing_counter= 0;
			return;
		} else if( rb5_on == 1 && prev_rb5_on != rb5_on ) {// 立ち上がりを待つ.
			idx_rec=store(idx_rec,timing_counter);//カウント値の記録.
			timing_counter= 0;
			return;
		}
	}
}

frame_status = 0で始まり、Frame先頭の「Leader」を検出して、056行で1に変わることで、キャリアの記憶モードに変わります。
最初の記憶は、070行で、これが「Leader」のキャリアの長さになります。(_MEMO3[3]〜に「Leader」の長さが記憶)
次の記憶はキャリア無しの長さで、_MEMO3[idx_rec]〜に記憶され、 次はキャリアあり長さが_MEMO3[idx_rec]〜と・・・交互に記憶される繰り返しです。
(idx_recは、store(idx_rec,timing_counter)で更新され、記憶するtiming_counterの大きさで次のidx_recが決まります。)
この繰り返しは、キャリア無しのカウント値がFRAME_END_COUNT_VALに達するまで続きます。
この長さだけキャリア無しが続くと判断された064行で、frame_status = 2が設定されて、受信処理は終わります。
以下に。この関数を示します。



記憶したリモコンパターンを送信する「snd_infrared() 」

送信時は、frame_status = 2で、上記Timer4割込みでsnd_infrared()を呼ぶことで行います。
_RB5 = 0; の赤外線LEDをOFFの状態から始まり、infrared_flagが1でキャリアあり、
0がキャリアなしで、timing_counter が0タイミングで交互に切り替わります。
infrared_flagが1でキャリアあり状態であれば、 『_RB5 = 1を1回、_RB5 = 0を2回]』行うように制御してキャリアを作ります。
以下に。この関数と残りのコードを示します。


int idx_snd=1;//送信のタイミング記憶位置 .
int infrared_flag = 0; // 赤外線LEDのキャリアON状態で1.
int timing_counter_t=0; // タイミングが変わる目標のタイミング.

void snd_infrared() // 赤外線送信.
{
	static int count = 0;
	if( idx_snd >= idx_rec ){// 送信終了?.
		frame_status = 2;
		return; 
	}

	if( timing_counter == 0 ){
		infrared_flag = ! infrared_flag;//キャリア反転.
		count = 0;
	}

	if( infrared_flag != 0 && count == 0 ){
		_RB5 = 1; // 赤外線LED点灯.
		__asm__ ("NOP");
	} else {
		_RB5 = 0;
		__asm__ ("NOP");
	}
	if(++count == 3) count = 0;// キャリア 1/3 duty生成.

	if(++timing_counter >= timing_counter_t){
		timing_counter = 0;
		idx_snd = restore(idx_snd, & timing_counter_t);//次のタイミング取得.
		//_send_decimal(  timing_counter_t,8);
		//_send_decimal(  idx_snd,8);
		//_send_string("<--  timing_counter_t, idx_snd\r\n");
	}
}


void timer4() //割り込み関数.
{
	static int print_flag = 0;
	if( frame_status < 2){
		print_flag = 1; 
		rec_infrared();//受信処理.
		return;
	} else if( frame_status == 3 ){
		print_flag = 1; 
		snd_infrared();//送信処理.
		return;
	}

	//static int count=0;//デバック確認用
	//if(count++ % 100000 != 0) return;

	if( print_flag == 0) return;

	int size = _get_capacity();
	if( size  < 10) return; //残りの出力バッファブロックが10未満なら出力しない。 .
	if( _request_acc_outbuff(_ID_ACCESS_T4_TASK) == 0 ) return; 

	_send_decimal(frame_status ,8);
	_send_string("<--frame_status \r\n");
	
	_send_decimal( idx_rec,8);
	_send_string("<-- idx_rec\r\n");

	int tc=0; 
	int idx= restore(3, & tc);
	_send_decimal( tc ,8);
	_send_string("<-- Leader\r\n");
	idx= restore(idx, & tc);
	_send_decimal( tc ,8);
	_send_string("<-- T0\r\n");
	idx= restore(idx, & tc);
	_send_decimal( tc ,8);
	_send_string("<-- T1\r\n");

	_release_acc_outbuff(_ID_ACCESS_T4_TASK);
	print_flag = 0;
}

__attribute__((address( 0x80005000 ))) void start (void);
void start()
{
	_send_string("START\r\n");

	if(frame_status == 2){// 既に受信が終わっている? .
		frame_status = 3;// 送信 
		timing_counter= 0;
		infrared_flag = 0; // 初期はキャリア無し(timing_counter==0時に反転).
		//最初のキャリアありのタイミング長を取得 .
		idx_snd = restore(3, &timing_counter_t);
		_send_decimal(  timing_counter_t,8);
		_send_decimal(  idx_snd,8);
		_send_string("<--  timing_counter_t, idx_snd\r\n");
		return;
	}
	prev_rb5_on=0;//RB5の初期化 
	_RB5 = 0; // 赤外線LEDをOFF 
	__asm__ ("NOP");
	_HANDLES[_IDX_INIT_TIMER_4_5] = init_timer4;// 割り込み初期化関数のデフォルトを変更 .
	_HANDLES[_IDX_TIMER_4_FUNC] = timer4;// 割り込み関数のデフォルトを変更登録 .
	init_timer4(); 
	T4CONbits.ON = 1;// Start timer4
	_RB15 = 0; // LED D1(黄緑)をOFF
}

プログラムロード時は、frame_status が0になっており、start()の実行でリモコン受信状態になります。
ここで、赤外線リモコンを受光部に向けて「テレビON」操作すると、受光信号のパターンを記憶して、frame_status が2になり、 次のような応答メッセージを出します。
(これは、Panasonic ブルーレイディスクレコーダー用リモコン N2QAYB000912での電源ON操作)

START:80005000
START
      +2<--frame_status 
    +241<-- idx_rec
    +396<-- Leader
    +203<-- T0
     +46<-- T1

この表示後の状態は、タイマ割込みでtimer4()を繰り返し実行中の状態ですが、 frame_status が2で、print_flagが0であるため、なにもしないことを繰り返しいている状態です。
ここで再びUSB通信で「START:80005000」よりstart()を実行をスタートさせると、 下記メッセージを出して、記憶したリモコンのパターンで発光します。 パターン発光が終わると再びframe_statusを2にして、なにもしない割込みループに戻ります。

START:80005000
START
    +397      +5<--  timing_counter_t, idx_snd
      +2<--frame_status 
    +241<-- idx_rec
    +396<-- Leader
    +203<-- T0
     +46<-- T1

start()を実行をスタートさせると、その都度に記憶したリモコンのパターンで発光します。
赤外線LEDをテレビ赤外線受光部に向けて実行して、「テレビのON動作」を確認できました。
なお、東芝のエアコンのリモコン動作も確認しましたが、全を試している訳ではないので、 正しく記憶できないパターンや、送信で動作しないパターンがあるかもしれません。