
この回路のモータ電源は図では3Vですが、実際は6V程必要です。
きゃ〜ぁ、恥ずかしい **(/▽/)**
これが今回利用したSHARP(AQuos)のTVリモコンです。
---------------------------------------------------------------------
#define IR_PIN 2 // 赤外線受信モジュール接続ピン
#define ML_PWM_PIN 3 // モーター(左)接続ピン
#define ML_IN1_PIN 4
#define ML_IN2_PIN 5
#define MR_PWM_PIN 6 // モーター(右)接続ピン
#define MR_IN1_PIN 8
#define MR_IN2_PIN 7
#define DATA_POINT 5 // 受信したデータから読取る内容のデータ位置
#define SPEED_OFFST 7 // 左右のモータ速度を合わせる為の調整用
int FR_flag ; // 前進・後進の状態フラグ
int LR_flag ; // 左右回転の状態フラグ
int Speed_L ; // モーター(左)の速度値
int Speed_R ; // モーター(右)の速度値
void setup()
{
pinMode(IR_PIN,INPUT) ; // 赤外線受信モジュール接続ピンを入力に設定
pinMode(ML_IN1_PIN,OUTPUT) ; // モーター(左)接続ピン1を出力に設定
pinMode(ML_IN2_PIN,OUTPUT) ; // モーター(左)接続ピン2を出力に設定
Speed_L = 0 ; // モーター(左)の速度を0に初期化
analogWrite(ML_PWM_PIN,0) ;
digitalWrite(ML_IN1_PIN, HIGH); // モーター(左)正転(前進)
digitalWrite(ML_IN2_PIN, LOW) ;
pinMode(MR_IN1_PIN,OUTPUT) ; // モーター(右)接続ピン1を出力に設定 (*1)
pinMode(MR_IN2_PIN,OUTPUT) ; // モーター(右)接続ピン2を出力に設定 (*1)
Speed_R = 0 ; // モーター(右)の速度を0に初期化
analogWrite(MR_PWM_PIN,0) ;
digitalWrite(MR_IN1_PIN, HIGH); // モーター(右)正転(前進)
digitalWrite(MR_IN2_PIN, LOW) ;
FR_flag = 0 ; // 前進状態に設定
LR_flag = 0 ; // 回転はしていない状態に設定
}
void loop()
{
int ans , l , r ;
ans = IRrecive() ; // 赤外線リモコンのデータを受信する
if (ans != 0) { // データを受信したら処理する
switch(ans) {
case 0xD8: // [>]ボタン:右回転
if (Speed_L == 0) {
// 停止中
Speed_R++ ;
if (Speed_R == 1) Speed_R = 2 ;
if (Speed_R >= 9) Speed_R = 9 ;
// 右モータを後進させる
digitalWrite(MR_IN1_PIN, LOW) ;
digitalWrite(MR_IN2_PIN, HIGH) ;
} else {
LR_flag = 1 ;
Speed_R-- ;
if (Speed_R <= 1) Speed_R = 0 ;
}
break ;
case 0xD7: // [<]ボタン:左回転
if (Speed_R == 0) {
// 停止中
Speed_L++ ;
if (Speed_L == 1) Speed_L = 2 ;
if (Speed_L >= 9) Speed_L = 9 ;
// 左モータを後進させる
digitalWrite(ML_IN1_PIN, LOW) ;
digitalWrite(ML_IN2_PIN, HIGH) ;
} else {
LR_flag = 2 ;
Speed_L-- ;
if (Speed_L <= 1) Speed_L = 0 ;
}
break ;
case 0x57: // [▲]ボタン:スピードUP
Speed_L++ ;
if (Speed_L == 1) Speed_L = 2 ;
if (Speed_L >= 9) Speed_L = 9 ;
Speed_R++ ;
if (Speed_R == 1) Speed_R = 2 ;
if (Speed_R >= 9) Speed_R = 9 ;
break ;
case 0x20: // [▼]ボタン:スピードDOWN
Speed_L-- ;
if (Speed_L <= 1) Speed_L = 0 ;
Speed_R-- ;
if (Speed_R <= 1) Speed_R = 0 ;
break ;
case 0xF5: // [終了]ボタン:回転終了
// 回転を停止させる処理
if (LR_flag != 0) { // 左右に回転中か?
if (LR_flag == 1) {
// 右回転中
Speed_R = Speed_L ;
} else {
// 左回転中
Speed_L = Speed_R ;
}
LR_flag = 0 ;
break ;
}
case 0x52: // [決定]ボタン:ブレーキ
// 前進・後進を停止させる処理
LR_flag = 0 ;
Speed_L = 0 ;
Speed_R = 0 ;
analogWrite(ML_PWM_PIN,0) ;
analogWrite(MR_PWM_PIN,0) ;
delayMicroseconds(500) ;
digitalWrite(ML_IN1_PIN, HIGH) ;
digitalWrite(ML_IN2_PIN, HIGH) ;
digitalWrite(MR_IN1_PIN, HIGH) ;
digitalWrite(MR_IN2_PIN, HIGH) ;
delay(500) ;
if (FR_flag != 0) {
digitalWrite(ML_IN1_PIN, LOW) ;
digitalWrite(ML_IN2_PIN, HIGH) ;
digitalWrite(MR_IN1_PIN, LOW) ;
digitalWrite(MR_IN2_PIN, HIGH) ;
} else {
digitalWrite(ML_IN1_PIN, HIGH) ;
digitalWrite(ML_IN2_PIN, LOW) ;
digitalWrite(MR_IN1_PIN, HIGH) ;
digitalWrite(MR_IN2_PIN, LOW) ;
}
break ;
case 0xbc: // [ツール]ボタン:前進/後進の切替え
if (Speed_L == 0 && Speed_R == 0) { // 停止中で切替えOK
if (FR_flag == 0) {
// 後進処理
FR_flag = 1 ;
digitalWrite(ML_IN1_PIN, LOW) ;
digitalWrite(ML_IN2_PIN, HIGH) ;
digitalWrite(MR_IN1_PIN, LOW) ;
digitalWrite(MR_IN2_PIN, HIGH) ;
} else {
// 前進処理
FR_flag = 0 ;
digitalWrite(ML_IN1_PIN, HIGH) ;
digitalWrite(ML_IN2_PIN, LOW) ;
digitalWrite(MR_IN1_PIN, HIGH) ;
digitalWrite(MR_IN2_PIN, LOW) ;
}
}
break ;
}
// スピードデータをPWM値に変更する
// 左モータの回転が右より早いのでここでPWM値を少し減らす
if (Speed_L == 2) l = map(Speed_L,0,9,0,255) - SPEED_OFFST ;
else l = map(Speed_L,0,9,0,255) - (SPEED_OFFST*Speed_L) ;
// l = map(Speed_L,0,9,0,255) ;
r = map(Speed_R,0,9,0,255) ;
// 実際にモータへPWM出力
analogWrite(ML_PWM_PIN,l) ; // 0-255(50-255)
analogWrite(MR_PWM_PIN,r) ; // 0-255(50-255)
delay(300) ; // 300msリモコンチャタリング防止
}
}
/*******************************************************************************
* IRrecive - 赤外線リモコンの送信データを受信する関数 *
* DATA_POINTで指定した位置のデータ(8ビット)を読み取ります。 *
* *
* 戻り: 読み取った整数値を返します *
*******************************************************************************/
int IRrecive()
{
unsigned long t ;
int i , j ;
int cnt , ans ;
char IRbit[64] ;
ans = 0 ;
t = 0 ;
if (digitalRead(IR_PIN) == LOW) {
// リーダ部のチェックを行う
t = micros() ; // 現在の時刻(us)を得る
while (digitalRead(IR_PIN) == LOW) ; // HIGH(ON)になるまで待つ
t = micros() - t ; // LOW(OFF)の部分をはかる
}
// リーダ部有りなら処理する(3.4ms以上のLOWにて判断する)
if (t >= 3400) {
i = 0 ;
while(digitalRead(IR_PIN) == HIGH) ; // ここまでがリーダ部(ON部分)読み飛ばす
// データ部の読み込み
while (1) {
while(digitalRead(IR_PIN) == LOW) ;// OFF部分は読み飛ばす
t = micros() ;
cnt = 0 ;
while(digitalRead(IR_PIN) == HIGH) {// LOW(OFF)になるまで待つ
delayMicroseconds(10) ;
cnt++ ;
if (cnt >= 1200) break ; // 12ms以上HIGHのままなら中断
}
t = micros() - t ;
if (t >= 10000) break ; // ストップデータ
if (t >= 1000) IRbit[i] = (char)0x31 ; // ON部分が長い
else IRbit[i] = (char)0x30 ; // ON部分が短い
i++ ;
}
// データ有りなら指定位置のデータを取り出す
if (i != 0) {
i = (DATA_POINT-1) * 8 ;
for (j=0 ; j < 8 ; j++) {
if (IRbit[i+j] == 0x31) bitSet(ans,j) ;
}
}
}
return( ans ) ;
}
---------------------------------------------------------------------
CIDEツールバーの赤枠部分「Upload」ボタンをクリックしてコンパイルとarduinoボードに書込みを行います。
#define DATA_POINT 5 // 受信したデータから読取る内容のデータ位置
case 0xD8: // [>]ボタン:右回転
case 0xD7: // [<]ボタン:左回転
case 0x57: // [▲]ボタン:スピードUP
case 0x20: // [▼]ボタン:スピードDOWN
case 0xF5: // [終了]ボタン:回転終了
case 0x52: // [決定]ボタン:ブレーキ
case 0xbc: // [ツール]ボタン:前進/後進の切替え
変更方法は前回の記事を読みましょう。
秋月通商のLCDオシロスコープキットでモータの出力を表示させて追記(*1) 2011/8/28
【きむ茶工房ガレージハウス】
Copyright (C) 2006-2020 Shigehiro Kimura All Rights Reserved.