PIC用のプログラムです。コンパイラはCCS Cを使用しています。かなり以前に組んだもののため、見苦しい点はご容赦ください。
#include "main.h" #include "CodeData.h" #include "IR.h" #include "Motion.h" #case // Case sensitive #define __16F88 #define __LIMIT // リミットスイッチの使用宣言 // -------------------------------------------------------------- #ifdef __16F876 #include <16f876.h> #fuses HS, NOWDT, PUT, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NOPROTECT #else #ifdef __16F88 #include <16f88.h> #fuses HS, NOWDT, NOPROTECT, PUT, NOBROWNOUT, NOLVP, NOCPD, MCLR #else #ifdef __16F84A #include <16f84A.h> #fuses HS, NOWDT, PUT, NOPROTECT #else #error This device in not supported!! #endif #endif #endif #device ADC=10 *=16 #use delay(Clock = 20000000) #use fast_io(A) #use fast_io(B) // ************************************************************************* #define MOTOR_LEFT1 PIN_B1 #define MOTOR_LEFT2 PIN_B2 #define MOTOR_RIGHT1 PIN_B3 #define MOTOR_RIGHT2 PIN_B4 #define MOTOR_ARM1 PIN_B5 #define MOTOR_ARM2 PIN_B6 #define LIMIT_UP PIN_A1 #define LIMIT_DOWN PIN_A0 #define LED PIN_A2 #define DRIVE_TIME 200 // モーター動作時間 [約 msec] #define STOP 0 #define GO 1 #define BACK 2 #define RIGHT 3 #define LEFT 4 #define UP 5 #define DOWN 6 #define IR_LED PIN_A2 // 受信確認用LED // ************************************************************************* int direction = STOP; // アーム用モーターの動作方向 /* ===================================================================== メイン関数 ===================================================================== */ void main() { #ifdef __LIMIT set_tris_a(0b00011011); #else set_tris_a(0b00000011); #endif output_a(0x00); set_tris_b(0b00000001); output_b(0x00); #ifndef __16F84A setup_adc_ports(NO_ANALOGS); // Set AD Converter setup_adc(ADC_OFF); #endif // ------------------------------------------------------ MotorTire(STOP); MotorArm (STOP); InitIR(); enable_interrupts(GLOBAL); FlashLED(2); while(1) { if(IR_ReceiveIF) ReceiveFromRC(); #ifdef __LIMIT CheckArmLimit(); #endif } } // ===================================================================== // 受信処理(赤外線リモコン) void ReceiveFromRC() { IR_ReceiveIF = FALSE; switch(IR_ReceiveData) { case RC_CODE_02: MotorTire(GO); break; case RC_CODE_08: MotorTire(BACK); break; case RC_CODE_05: MotorTire(STOP); break; case RC_CODE_04: MotorTire(LEFT); break; case RC_CODE_06: MotorTire(RIGHT); break; #ifdef __LIMIT case RC_CODE_ChUP: MotorArm(UP); break; case RC_CODE_ChDOWN: MotorArm(DOWN); break; #endif case RC_CODE_VolUP: MotorArmTime(UP); break; case RC_CODE_VolDOWN: MotorArmTime(DOWN);break; case RC_CODE_10: Motion(1); break; case RC_CODE_11: Motion(2); break; case RC_CODE_12: Motion(3); break; default: break; } } // ===================================================================== // タイヤ用モーター駆動 void MotorTire(int select) { int leftOut1, leftOut2, rightOut1, rightOut2; switch(select) { case STOP: leftOut1 = 0; leftOut2 = 0; rightOut1 = 0; rightOut2 = 0; break; case GO: leftOut1 = 0; leftOut2 = 1; rightOut1 = 0; rightOut2 = 1; break; case BACK: leftOut1 = 1; leftOut2 = 0; rightOut1 = 1; rightOut2 = 0; break; case RIGHT: leftOut1 = 0; leftOut2 = 1; rightOut1 = 1; rightOut2 = 0; break; case LEFT: leftOut1 = 1; leftOut2 = 0; rightOut1 = 0; rightOut2 = 1; break; default: return; } // モーターへ出力 output_bit(MOTOR_LEFT1, leftOut1 ); output_bit(MOTOR_LEFT2, leftOut2 ); output_bit(MOTOR_RIGHT1, rightOut1); output_bit(MOTOR_RIGHT2, rightOut2); } // タイヤ用の右モーター駆動 void Right(int select) { switch(select) { case 0: output_bit(MOTOR_RIGHT1, 0); output_bit(MOTOR_RIGHT2, 0); break; // 停止 case 1: output_bit(MOTOR_RIGHT1, 0); output_bit(MOTOR_RIGHT2, 1); break; // 正転 case 2: output_bit(MOTOR_RIGHT1, 1); output_bit(MOTOR_RIGHT2, 0); break; // 逆転 default: break; } } // タイヤ用の左モーター駆動 void Left(int select) { switch(select) { case 0: output_bit(MOTOR_LEFT1, 0); output_bit(MOTOR_LEFT2, 0); break; // 停止 case 1: output_bit(MOTOR_LEFT1, 0); output_bit(MOTOR_LEFT2, 1); break; // 正転 case 2: output_bit(MOTOR_LEFT1, 1); output_bit(MOTOR_LEFT2, 0); break; // 逆転 default: break; } } // アーム用モーター駆動 void MotorArm(int select) { int out1, out2; switch(select) { case STOP: out1 = 0; out2 = 0; break; case UP: out1 = 1; out2 = 0; break; case DOWN: out1 = 0; out2 = 1; break; default: return; } // モーターへ出力 output_bit(MOTOR_ARM1, out1); output_bit(MOTOR_ARM2, out2); direction = select; } void Arm(int select) { switch(select) { case 0: MotorArm(STOP); break; case 1: MotorArm(UP ); break; case 2: MotorArm(DOWN); break; default: return; } } // アーム用モーターを一定時間駆動する void MotorArmTime(int select) { long i; MotorArm(select); for(i=0; i<DRIVE_TIME; i++) { #ifdef __LIMIT CheckArmLimit(); if(direction == STOP) break; #endif delay_ms(1); } MotorArm(STOP); } // 指定時間の遅延 ( time[sec] ) void Time(float time) { int i; int num; // 100msec を指定値を10倍した回数だけ繰り返す // ex) time = 1.0 ならば 100msec x 10 = 1.0sec num = (int)(time * 10); for(i=0; i<num; i++) { if(IR_ReceiveIF) break; #ifdef __LIMIT CheckArmLimit(); #endif delay_ms(100); } } // アームの上下限チェック void CheckArmLimit() { if(!input(LIMIT_UP) && direction == UP) { delay_us(10); if(!input(LIMIT_UP)) MotorArm(STOP); } if(!input(LIMIT_DOWN) && direction == DOWN) { delay_us(10); if(!input(LIMIT_DOWN)) MotorArm(STOP); } } // ===================================================================== // LED点滅 void FlashLED(int num) { num <<= 1; for(; num; num--) { output_bit(IR_LED, num & 0x01); delay_ms(200); } output_low(IR_LED); }
テレビなどの赤外線リモコンの信号を解析します。
#include "IR.h" // 赤外線リモコン #define ERR_RANGE 2 // ビット幅 許容誤差 [カウント数] #define BIT_MAX 32 // ビット数 最大値 (変更時は受信バッファの型も変更すること) #define MAKER_MAX 6 // 対応メーカー数 #define BIT_START 0 #define BIT_HI 1 #define BIT_LO 2 int32 IR_ReceiveData; // 赤外線 受信データ int IR_count; // カウント数 short IR_ReceiveIF = FALSE; // 受信完了フラグ short IR_lengthAna = FALSE; // ビット幅 解析フラグ // ===================================================================== // 赤外線リモコン 受信処理 #ifdef IR_CCP1 #INT_CCP1 #else #INT_EXT #endif void IntReceive() { static int count; // 受信ビット数 static int32 Signal // バフ int Data; int detect; Data = get_timer0(); set_timer0(0x00); // ビット幅 解析モードか? if(IR_lengthAna) { IR_count = Data; IR_ReceiveIF = TRUE; // 受信完了フラグセット return; } // ビット幅 判別 if (AllowArea(Data, RC_HI )) detect = BIT_HI; else if(AllowArea(Data, RC_LO )) detect = BIT_LO; else if(AllowArea(Data, RC_START)) detect = BIT_START; else return; // ノイズと判断 // スタートビットか? if(detect == BIT_START) { #ifdef IR_LED_REV output_high(IR_LED); #else output_low(IR_LED); #endif Signal = 0x00000000; count = 0; return; } count++; // ビット数カウント // 信号フォーマットのビット数がBIT_MAX より大きいならば // それを超える最初のビット数分だけ読み飛ばす if(RC_BIT_SUM > BIT_MAX) { if(count <= RC_BIT_SUM - BIT_MAX) { return; } } switch(detect) { case BIT_HI: Signal <<= 1; Signal++; break; // High case BIT_LO: Signal <<= 1; break; // Low default: } if(count == RC_BIT_SUM) { IR_ReceiveData = Signal; IR_ReceiveIF = TRUE; // 受信完了フラグセット #ifdef IR_LED_REV output_low (IR_LED); // LED点灯 #else output_high(IR_LED); // LED消灯 #endif } } // ===================================================================== // 受信データの解析(赤外線リモコン) #ifdef RC_ANA int RC_AnalyzeData(int CheckData) { IR_ReceiveIF = FALSE; // フラグクリア switch(CheckData) { // コード判別 case RC_CODE_01: return 1; // Button[ 1] case RC_CODE_02: return 2; // Button[ 2] case RC_CODE_03: return 3; // Button[ 3] case RC_CODE_04: return 4; // Button[ 4] case RC_CODE_05: return 5; // Button[ 5] case RC_CODE_06: return 6; // Button[ 6] case RC_CODE_07: return 7; // Button[ 7] case RC_CODE_08: return 8; // Button[ 8] case RC_CODE_09: return 9; // Button[ 9] case RC_CODE_10: return 10; // Button[10] case RC_CODE_11: return 11; // Button[11] case RC_CODE_12: return 12; // Button[12] case RC_CODE_VolUP: return 13; // Button[VolUP ] case RC_CODE_VolDOWN: return 14; // Button[VolDown] case RC_CODE_ChUP: return 15; // Button[ChannelUP ] case RC_CODE_ChDOWN: return 16; // Button[ChannelDown] default: return 0x00; // 該当なし } } #endif // ===================================================================== // 赤外線通信の初期化 void InitIR() { setup_timer_0(RTCC_INTERNAL | RTCC_DIV_256); // タイマ0設定 #ifdef IR_CCP1 setup_ccp1(CCP_CAPTURE_FE); // CCP1 (CRVP1738 は負論理) enable_interrupts(INT_CCP1); // 割り込み許可 #else ext_int_edge(H_TO_L); // 外部INT enable_interrupts(INT_EXT); // 割り込み許可 #endif #ifdef IR_LED_REV output_low (IR_LED); // LED点灯 #else output_high(IR_LED); // LED消灯 #endif } // ===================================================================== // 誤差 許容可否判定 short AllowArea(int Object, int Scope) { if(Scope - ERR_RANGE > Object) return FALSE; if(Scope + ERR_RANGE < Object) return FALSE; return TRUE; }
使用するリモコンに合わせて、そのコードをここに定義します。
#define RC_CODE_VolUP 0x0 // 未使用 #define RC_CODE_VolDOWN 0x1 // // ----------------------------------------- #define RC_BIT_SUM 32 #define RC_START 0x05 #define RC_HI 0x2C #define RC_LO 0x16 #define RC_CODE_02 0x18E78877 #define RC_CODE_08 0x18E7E817 #define RC_CODE_05 0x18E728D7 #define RC_CODE_04 0x18E7C837 #define RC_CODE_06 0x18E7A857 #define RC_CODE_ChUP 0x18E740BF #define RC_CODE_ChDOWN 0x18E7C03F #define RC_CODE_10 0x18E79867 #define RC_CODE_11 0x18E758A7 #define RC_CODE_12 0x18E7D827
ロボットの動作パターンを、プログラミングで変更できるようにしてあります。
void Motion(int mode) { #ifdef __LIMIT // アームを下限まで下げる MotorArmTime(DOWN); MotorArmTime(DOWN); MotorArmTime(DOWN); MotorArmTime(DOWN); MotorArmTime(DOWN); // 少しだけ上げておく MotorArmTime(UP ); #endif switch(mode) { case 1: // ------------------------------------------------------- Right(1); Left(1); Arm(0); Time(1.0); // 前へ進んで Right(2); Left(1); Arm(0); Time(0.9); // 右を向く Right(1); Left(1); Arm(0); Time(1.0); // 前へ進んで Right(2); Left(1); Arm(0); Time(0.9); // 右を向く Right(1); Left(1); Arm(0); Time(1.0); // 前へ進んで Right(2); Left(1); Arm(0); Time(0.9); // 右を向く Right(1); Left(1); Arm(0); Time(1.0); // 前へ進んで Right(2); Left(1); Arm(0); Time(0.9); // 右を向く // ------------------------------------------------------- break; case 2: // ------------------------------------------------------- Right(1); Left(1); Arm(0); Time(1.0); // 前へ進む Right(0); Left(0); Arm(0); Time(0.2); // 少し待つ Right(0); Left(0); Arm(1); Time(1.0); // 腕を上げる Right(0); Left(0); Arm(0); Time(0.2); // 少し待つ Right(2); Left(2); Arm(0); Time(1.0); // 後ろへ下がる Right(0); Left(0); Arm(2); Time(1.0); // 腕を下げる // ------------------------------------------------------- break; case 3: // ------------------------------------------------------- Right(2); Left(1); Arm(0); Time(0.2); // 体を左右に振る Right(1); Left(2); Arm(0); Time(0.4); // Right(2); Left(1); Arm(0); Time(0.4); // Right(1); Left(2); Arm(0); Time(0.4); // Right(2); Left(1); Arm(0); Time(0.4); // Right(1); Left(2); Arm(0); Time(0.2); // Right(0); Left(0); Arm(0); Time(0.2); // 少し待つ Right(0); Left(0); Arm(1); Time(0.4); // 腕を2回 上下に振る Right(0); Left(0); Arm(2); Time(0.4); // Right(0); Left(0); Arm(1); Time(0.4); // Right(0); Left(0); Arm(2); Time(0.4); // Right(0); Left(0); Arm(0); Time(0.2); // 少し待つ Right(2); Left(1); Arm(1); Time(0.8); // 体左右に Right(1); Left(2); Arm(2); Time(0.8); // 腕を上下に振る Right(1); Left(2); Arm(1); Time(0.8); // Right(2); Left(1); Arm(2); Time(0.8); // Right(1); Left(1); Arm(0); Time(1.0); // 前に進んで Right(2); Left(1); Arm(0); Time(0.9); // 右を向く Right(0); Left(0); Arm(0); Time(0.2); // 少し待つ Right(1); Left(1); Arm(0); Time(0.3); // 前後にステップ Right(2); Left(2); Arm(0); Time(0.3); // Right(1); Left(1); Arm(0); Time(0.3); // Right(2); Left(2); Arm(0); Time(0.3); // Right(1); Left(1); Arm(0); Time(0.3); // Right(2); Left(2); Arm(0); Time(0.3); // Right(1); Left(2); Arm(1); Time(1.1); // 腕を上げながら正面を向く Right(0); Left(0); Arm(1); Time(0.5); // 腕を高く上げる Right(0); Left(0); Arm(2); Time(0.3); // 腕を上下に振る Right(0); Left(0); Arm(1); Time(0.3); // Right(0); Left(0); Arm(2); Time(0.3); // Right(2); Left(1); Arm(1); Time(0.7); // 腕を上下させながら後ろを向く Right(2); Left(1); Arm(2); Time(0.7); // Right(2); Left(1); Arm(1); Time(0.8); // Right(1); Left(1); Arm(0); Time(1.0); // 前へ進んで 最初の位置へ戻る Right(1); Left(2); Arm(0); Time(1.8); // 左回転で正面を向く Right(0); Left(0); Arm(0); Time(0.4); // 少し待つ Right(0); Left(0); Arm(2); Time(1.0); // 腕を下げる // ------------------------------------------------------- break; default: break; } MotorTire(STOP ); MotorArm (STOP ); }