![]()
ビクターモードのリモコンでも操作はできます。
受信信号の状態(リモコン受信データ(Victor))を確認してプログラムを変更すればOKです。
なお、受信データは私が確認したものです。
メーカから公表されたものではありません。(ご注意ください!)
前に記したSONYモード、SHARPモード、三菱モードのリモコンと組み合わせれば
4台の「梵天丸」を別々に操作できます。(そんなに持っている人は少ないと思うが・・・)
以下がサンプルプログラムのソースリストです。
//******************************************************************************
//* bon_ir_vt スタートビット検出+リモコンデータ検出 *
//* Victorリモコンを押すと梵天丸移動 *
//******************************************************************************
#include <16f84a.h> // 使用デバイスの定義情報をインクルードする。
#fuses HS, NOWDT, NOPROTECT // コンフィグレーションの設定(HSモード,WDTなし,プロテクトなし)
#use delay (clock=8000000) // 梵天丸の発振子の周波数8MHz 時間待ち関数(delay)の設定
//-----------------------------------------------------------------------------
// I/Oポートの定義
//-----------------------------------------------------------------------------
#byte RA = 5 // ポートAのアドレス5番地をRA:文字変数に設定する。
#byte RB = 6 // ポートBのアドレス6番地をRB:文字変数に設定する。
#bit start_bit = RA.4 // 赤外線の入力ポートRA4をstart_bit:文字変数に設定する。
//-----------------------------------------------------------------------------
// メイン関数
//-----------------------------------------------------------------------------
main(){
byte flag, cnt, i ,j; // byte型変数(符号なし8ビット)
byte data1, data2, data3, data4, data5, data6, data7, data8, data9;
byte rcv, rcv1, rcv2, rcv3, rcv4;
set_tris_a(0x10); // ポートAはRA4のみ入力に設定。(1:Input) 他は出力に設定。(0:Output)
set_tris_b(0x00); // ポートBはすべて出力に設定(0:Output)
data1 = 0x01; // 前左 パターン 0000 0001 モータ動作データ
data2 = 0x03; // 前進 パターン 0000 0011 リモコンのボタンとdataの番号が対応
data3 = 0x02; // 前右 パターン 0000 0010 下位4ビットが
data4 = 0x09; // 左転 パターン 0000 1001 (MSB)左逆転 右逆転 左正転 右正転(LSB)
data5 = 0x00; // 停止 パターン 0000 0000
data6 = 0x06; // 右転 パターン 0000 0110
data7 = 0x04; // 後左 パターン 0000 0100
data8 = 0x0c; // 後進 パターン 0000 1100
data9 = 0x08; // 後右 パターン 0000 1000
RA = 0x00; // 電源オン時、モータを停止状態にしておく
while(1){
while(start_bit!=0) {} // スタートビットが入力されるまで待つ
flag = 0;
delay_us(8520);
for (i=1;i<=13;i++) // スタートビット検出
{ // 300μs×13=3900μsのうちに
delay_us(300); // RA4の"H"レベルの回数を検出
if (input(PIN_A4)==1)
flag = flag + 1;
}
delay_us(860);
for (j=1;j<=2;j++)
{
for (i=1;i<=5;i++) // スタートビット検出
{ // 250μs×5=1250μsのうちに
delay_us(250);
if (input(PIN_A4)==1) // RA4の"H"レベルの回数を検出
flag = flag + 1;
}
delay_us(870);
}
if (flag >=20) // 20回以上検出した場合は
{
delay_us(6150);
rcv = 0, rcv1 = 0, rcv2 = 0, rcv3 = 0, rcv4 = 0, cnt = 0 ;
for (i=1;i<=10;i++) //1ビット目
{
delay_us(108); // 100μs×10=1000μsのうちに
if (input(PIN_A4)==1) // RA4の"L"レベルの回数を検出
cnt = cnt + 1; // 検出の場合 cnt値+1
else
cnt = cnt + 0; // 未検出の場合 cnt値+0
}
if (cnt >=8) // cnt値が8以上の場合
{
rcv1 =1; // 1,3,5,7,9のボタンが押された場合
delay_us(1040); // 次のデータビットまで待機
}
else
{
rcv1 =0; // 2,4,6,8のボタンが押された場合
}
cnt = 0; // cnt値の初期化
for (i=1;i<=10;i++) //2ビット目
{
delay_us(108);
if (input(PIN_A4)==1)
cnt = cnt + 1;
else
cnt = cnt + 0;
}
if (cnt >=8)
{
rcv2 = 2; // 2,3,6,7のボタンが押された場合
delay_us(1040);
}
else
{
rcv2 = 0; // 1,4,5,8,9のボタンが押された場合
}
cnt = 0;
for (i=1;i<=10;i++) //3ビット目検出
{
delay_us(108);
if (input(PIN_A4)==1)
cnt = cnt + 1;
else
cnt = cnt + 0;
}
if (cnt >=8)
{
rcv3 = 4; // 4,5,6,7のボタンが押された場合
delay_us(1040);
}
else
{
rcv3 = 0; // 1,2,3,8,9のボタンが押された場合
}
cnt = 0;
for (i=1;i<=10;i++) //4ビット目検出
{
delay_us(108);
if (input(PIN_A4)==1)
cnt = cnt + 1;
else
cnt = cnt + 0;
}
if (cnt >=8)
{
rcv4 = 8; // 8,9のボタンが押された場合
// delay_us(1040);
}
else
{
rcv4 = 0; // 1,2,3,4,5,6,7のボタンが押された場合
}
rcv =rcv1 + rcv2 + rcv3 + rcv4; // 検出データ加算
}
switch(rcv) // リモコンデータ検出結果
{
case 1 : RA = data1; // リモコンボタン"1" 押す 前左
break;
case 2 : RA = data2; // リモコンボタン"2"押す 前進
break;
case 3 : RA = data3; // リモコンボタン"3"押す 前右
break;
case 4 : RA = data4; // リモコンボタン"4"押す 左回転
break;
case 5 : RA = data5; // リモコンボタン"5"押す 停止
break;
case 6 : RA = data6; // リモコンボタン"6"押す 右回転
break;
case 7 : RA = data7; // リモコンボタン"7"押す 後左
break;
case 8 : RA = data8; // リモコンボタン"8"押す 後進
break;
case 9 : RA = data9; // リモコンボタン"9"押す 後右
break;
}
delay_ms(200); // 4連送データの2,3、4回目をキャンセルする
} // 無限ループで繰り返し
}
平成16年1月10日作成