ロボットの車体はタミヤの楽しい工作「タミヤ 楽しい工作シリーズ No.104 ブルドーザー工作基本セット」を使用しました。
コントローラー部は使わないので切ってしまい、モータードライバーIC「TA7291P」(\150@秋月)で制御することにします。
このモータードライバーICは正転逆転可能で、外付け部品が少なく、5V系でコントロールできます。
電源はエネループ4本の4.8Vを使用しましたが、このICの出力飽和電圧は1V程度なのでFA-130モーターには3.8V程度
加わることになります。よって、推奨電圧からは27%ほどオーバーして使用することになります。
コントロールするマイコンは「PIC16F648A」(\200@秋月)で、内蔵クロック4MHzで使用します。
モーター制御は1モーター当たり2ポート必要です。PORT_BはCCPやUARTと超音波センサで使うのでPORT_Aを使います。
また、攻撃用(?)のクラッカーの紐を引くモーターも追加したので、合計6ポート必要でした。
今回は、PORT_Aのうち、オープンドレイン専用の4と入力専用の5を避けて、0,1,2,3,6,7を使いました。
キャタピラーなので、超信地回転も可能です。
前照灯は放熱基板付1WハイパワーフルカラーRGBLED 「OSTCWBTHC1S」(\250@秋月)を使用しました。
RGBのそれぞれのポートの組み合わせで、7色に変化させることが出来ます。
色を選択するのはハイサイド側で行うこととして、デバイスは2SJ681(\40@秋月)+RN1201(\5@秋月)を選択しました。
LEDには最大で各色200mA、標準で150mA流せるようですが、色味をみながら抵抗値を赤22Ω、青と緑は10Ωとした結果、
赤が107mA、緑が142mA、青が139mAとなりました。
この場合、LEDが消費する電力は合計で1.2W程度で、直視できないほどの明るさです。
電流制限用の抵抗は1Wの酸化金属皮膜抵抗を奢ったのですが、1/2Wの安いカーボン抵抗でも問題ない損失でした。
3色のLEDはカソードコモンとして、PWM制御して明るさを調整します。
人間の目は対数スケールで明るく感じることと、8bitのマイコンの8bitのPWMを使用する都合で、0,1,2,4,8,16,32,64,128,255の10段階としました。
ローサイド側のFETは2SK2201(\70@千石)を使用しました。コントロールする電流は最大で400mA程度しかないので、発熱は少なく、問題ありません。
超音波センサは、HC-SR04を使用しました。
車体に固定した際に干渉するので、ピンヘッダを表裏逆にしています。
タイマ割り込みで0.52秒に一度距離を測定し、Node.jsに送っています。
ループ内で反射時間を測定します。.lstファイルを見ると一カウント当たり11サイクル=11usかかっているようでした。
よって、カウンタと距離の関係は、カウンタ値をdistanceとし、音速を340m/sとすると、340*11*distance/10^6*100/2(cm) = 0.187 * distance (cm)となります。
マイコンではカウント数のみを文字列で送り、割り算はnode.js側でやってもらいます。
実験した限りでは誤差2%程度だったので、おそらく計算式はあっていると思われます。
この超音波センサはたまに応答が無くなることがあるので、タイムアウトした場合前回の値を返すようにしています。
接続されていない場合は65535を返し続けます。
また、距離をマイコン側でも監視して、およそ20cm以内に障害物があれば停止するようにしました。
クラッカーはホームセンターで買った金具でホールドし、タミヤの4速パワーギヤボックスHE 72007を74:1で使用しました。
クラッカーを引けるかトルクが心配だったのですが、楽勝でした。
/***************robot.c********** | |
node-serialportから制御できるロボットを作るため | |
UART入力でモーターを制御する。 | |
追加機能でクラッカーを引く&超音波センサで距離を読み取る。 | |
*****************************************/ | |
#include <16F648A.h> | |
#fuses INTRC_IO,NOWDT,PUT,NOPROTECT,NOMCLR | |
#use delay(CLOCK = 4000000) //4MHz | |
#use rs232(baud=9600,parity=N,xmit=PIN_B2,rcv=PIN_B1) //ハードウェアUART | |
#use fast_io(a) | |
#use fast_io(b) | |
/***************PINについて****************** | |
A0,A1 モーター1 | |
A2,A3 モーター2 | |
A6,A7 モーター3 | |
B1,B2 RX,TX | |
B3/CCP LED コモン カソード | |
B4 LED 赤アノード | |
B5 LED 青アノード | |
B6 LED 緑アノード | |
B0 超音波センサ入力 | |
B7 超音波センサトリガ | |
*****************************************/ | |
#define MOTOR1A PIN_A0 | |
#define MOTOR1B PIN_A1 | |
#define MOTOR2A PIN_A3 | |
#define MOTOR2B PIN_A2 | |
#define MOTOR3A PIN_A6 | |
#define MOTOR3B PIN_A7 | |
#define MSTP_US 700 | |
#define LED_R PIN_B6 | |
#define LED_G PIN_B4 | |
#define LED_B PIN_B5 | |
#define LED_COM PIN_B3 | |
#define SS_ECHO PIN_B0 | |
#define SS_TRIG PIN_B7 | |
#define SS_ATSND PIN_A4 | |
#define STOP_DISTANCE 100 //100*0.187=18.7cm | |
#define LONG_MAX 65535 | |
/************スレッドについて****************** | |
タイマ割り込みで約0.5秒に一回距離を測定する。 | |
timer2はccpで使う。 | |
*****************************************/ | |
//グローバル変数の定義 | |
int led_bright; | |
int command; | |
void motor1_foward() | |
{ | |
output_low(MOTOR1A); | |
output_low(MOTOR1B); | |
delay_us(MSTP_US); | |
output_high(MOTOR1A); | |
} | |
void motor1_back() | |
{ | |
output_low(MOTOR1A); | |
output_low(MOTOR1B); | |
delay_us(MSTP_US); | |
output_high(MOTOR1B); | |
} | |
void motor1_stop() | |
{ | |
output_low(MOTOR1A); | |
output_low(MOTOR1B); | |
delay_us(MSTP_US); | |
} | |
void motor2_foward() | |
{ | |
output_low(MOTOR2A); | |
output_low(MOTOR2B); | |
delay_us(MSTP_US); | |
output_high(MOTOR2A); | |
} | |
void motor2_back() | |
{ | |
output_low(MOTOR2A); | |
output_low(MOTOR2B); | |
delay_us(MSTP_US); | |
output_high(MOTOR2B); | |
} | |
void motor2_stop() | |
{ | |
output_low(MOTOR2A); | |
output_low(MOTOR2B); | |
delay_us(MSTP_US); | |
} | |
void motor3_foward() | |
{ | |
output_low(MOTOR3A); | |
output_low(MOTOR3B); | |
delay_us(MSTP_US); | |
output_high(MOTOR3A); | |
} | |
void motor3_back() | |
{ | |
output_low(MOTOR3A); | |
output_low(MOTOR3B); | |
delay_us(MSTP_US); | |
output_high(MOTOR3B); | |
} | |
void motor3_stop() | |
{ | |
output_low(MOTOR3A); | |
output_low(MOTOR3B); | |
delay_us(MSTP_US); | |
} | |
long distance, distance_old; | |
/*タイマ割り込みで約0.52秒に1回距離を測定する*/ | |
#INT_TIMER1 | |
void timer1_isr(){ | |
set_timer1(LONG_MAX); | |
output_high(SS_TRIG); | |
delay_us(10); | |
output_low(SS_TRIG); | |
distance = 0; | |
while(!input(SS_ECHO) && distance != LONG_MAX){ //echoがHIになるのを待つ | |
distance++; //センサが繋がっていない時はタイムアップするようにする。 | |
} | |
distance = 0; | |
while(input(SS_ECHO) && distance != LONG_MAX){ //echoが帰ってきている間カウントアップ。 | |
distance++; //なぜかechoがHのまま固まってしまうことがある。 | |
} | |
//超音波センサがバグっていたら前回の値で上書きする。 | |
if (distance == 0 || distance == LONG_MAX){ | |
distance = distance_old; | |
}else{ | |
distance_old = distance; | |
} | |
/* | |
//結果の出力。割り算とかはパソコンにしてもう。 | |
//ちなみに.lstファイルによると、11命令で1加算、4MHzでは1命令=1usなので | |
//音速を340m/sとすると、340*11*distance/10^6*100/2(cm) = 0.187 * distance (cm)となる。 | |
*/ | |
if(!input(SS_ATSND)){ | |
printf("%Lu\r\n",distance); | |
} | |
//障害物が近くにあったら停止 | |
if(distance < STOP_DISTANCE){ | |
motor1_stop(); | |
motor2_stop(); | |
} | |
} | |
/*メイン関数*/ | |
void main() | |
{ | |
set_tris_a(0b00110000); //a4,a5は入力( | |
set_tris_b(0b00000011); //b0,b1は入力 | |
//1サイクル4クロックなので実質1MHz、8分周しているので125kHz | |
//割り込みは8us毎に発生、timerを0xffに設定すると524.28ms毎に割り込み発生 | |
setup_timer_1(T1_INTERNAL | T1_DIV_BY_8); //T1_DIVは8まで。 | |
set_timer1(LONG_MAX); | |
output_low(SS_TRIG); | |
distance_old = LONG_MAX; | |
//LEDの明るさ調整用CCP/PWM設定 | |
setup_oscillator(OSC_4MHZ); | |
setup_ccp1(CCP_PWM); | |
setup_timer_2(T2_DIV_BY_1,255,1); | |
set_pwm1_duty(32); | |
led_bright = 0; | |
output_high(LED_R); | |
output_high(LED_G); | |
output_high(LED_B); | |
motor1_stop(); | |
motor2_stop(); | |
motor3_stop(); | |
enable_interrupts(INT_TIMER1); //タイマ1割込み許可 | |
enable_interrupts(GLOBAL); | |
while(true) | |
{ | |
if(kbhit()){ | |
command = getc(); | |
switch(command){ | |
case 'a' : //左回転 | |
motor1_foward(); | |
motor2_stop(); | |
break; | |
case 's' : //後退 | |
motor1_back(); | |
motor2_back(); | |
break; | |
case 'd' : //右回転 | |
motor1_stop(); | |
motor2_foward(); | |
break; | |
case 'w' : //前進 | |
motor1_foward(); | |
motor2_foward(); | |
break; | |
case 'q' : //停止 | |
motor1_stop(); | |
motor2_stop(); | |
motor3_stop(); | |
break; | |
case 'z' : //左急回転 | |
motor1_foward(); | |
motor2_back(); | |
break; | |
case 'c' : //右急回転 | |
motor1_back(); | |
motor2_foward(); | |
break; | |
case 'e' : //クラッカー引く | |
motor3_foward(); | |
break; | |
case 'x' : //クラッカー戻す | |
motor3_back(); | |
break; | |
case '9' : //LED明るさ | |
led_bright += 127; | |
case '8' : //LED明るさ | |
led_bright += 64; | |
case '7' : //LED明るさ | |
led_bright += 32; | |
case '6' : //LED明るさ | |
led_bright += 16; | |
case '5' : //LED明るさ | |
led_bright += 8; | |
case '4' : //LED明るさ | |
led_bright += 4; | |
case '3' : //LED明るさ | |
led_bright += 2; | |
case '2' : //LED明るさ | |
led_bright += 1; | |
case '1' : //LED明るさ | |
led_bright += 1; | |
case '0' : //LED消灯 | |
set_pwm1_duty(led_bright); | |
led_bright = 0; | |
break; | |
case 'r' : //LED赤 | |
output_high(LED_R); | |
output_low(LED_G); | |
output_low(LED_B); | |
break; | |
case 't' : //LED緑 | |
output_low(LED_R); | |
output_high(LED_G); | |
output_low(LED_B); | |
break; | |
case 'y' : //LED青 | |
output_low(LED_R); | |
output_low(LED_G); | |
output_high(LED_B); | |
break; | |
case 'u' : //LEDシアン | |
output_low(LED_R); | |
output_high(LED_G); | |
output_high(LED_B); | |
break; | |
case 'i' : //LEDマゼンダ | |
output_high(LED_R); | |
output_low(LED_G); | |
output_high(LED_B); | |
break; | |
case 'o' : //LED黄 | |
output_high(LED_R); | |
output_high(LED_G); | |
output_low(LED_B); | |
break; | |
case 'p' : //LED白 | |
output_high(LED_R); | |
output_high(LED_G); | |
output_high(LED_B); | |
break; | |
case '?' : //距離を送信 | |
printf("%Lu\r\n",distance); | |
break; | |
default : | |
break; | |
} | |
} | |
} | |
} |
//LEDの色を選ぶ | |
var colorArray = ["#FF0000", "#00FF00", "#0000FF", "#00FFFF", "#FF00FF", "#FFFF00", "#FFFFFF"]; | |
var colorCommand = ["r", "t", "y", "u", "i", "o", "p"]; | |
var socket = io(); | |
socket.on('distance', function (data) { | |
$('h1').text(data); | |
}); | |
socket.on('sendedcommand', function (data) { | |
var numData; | |
numData = parseInt(data); | |
if (numData < 10) { | |
$('input').val(numData); //ブラウザ間でLED輝度を連動させる | |
} | |
//ブラウザ間で同期してhrラインに色を付ける。高さを指定しないと、色が付かないのでcssで指定。 | |
if ($.inArray(data, colorCommand) != -1) { | |
var colorIndex = $.inArray(data, colorCommand); | |
$('hr').css("background-color",colorArray[colorIndex] ); | |
} | |
data = "Send Command: '" + data + "'" | |
$('h4').text(data); | |
}); | |
$('input[type=range]').change(function () { | |
var val = $(this).val(); | |
socket.emit('sendcommand', val); | |
}); | |
$("#icolor2").icolor({ | |
flat: true, | |
colors: ["FF0000", "00FF00", "0000FF", "FFFF00", "FF00FF", "00FFFF", "FFFFFF"], | |
col: false, | |
onSelect: function (c) { | |
//this.$tb.css("background-color", c); | |
n = $.inArray(c, colorArray); | |
socket.emit('sendcommand', colorCommand[n]); | |
} | |
}); | |
// モーターコントロールボタンのクリックイベントを設定 | |
var buttonList = ["Up", "Right", "Left", "Down", "Stop", "TurnR", "TurnL", "Pull","Send"]; | |
var commandList = ["w", "d", "a", "s", "q", "z", "c", "e","x"]; | |
for (var i = 0; i < buttonList.length; i++) { | |
var ele = document.getElementById(buttonList[i]); | |
ele.addEventListener("click", function () { | |
n = $.inArray(this.id, buttonList); | |
socket.emit('sendcommand', commandList[n]); | |
}, true); | |
} |
var express = require('express'); | |
var app = require('express')(); | |
var http = require('http').Server(app); | |
var port = process.env.port || 1337; | |
var io = require('socket.io')(http); | |
var SerialPort = require('serialport').SerialPort; | |
var serial = new SerialPort('COM1', { //SZはCOM3 | |
baudrate: 9600 | |
}); | |
var statusStr: string = "."; | |
var civCommandTmp = ""; | |
app.use(express.static(__dirname + '/public')); | |
app.get('/', function (req, res) { | |
res.sendfile('index.html'); | |
}); | |
http.listen(3000, function () { | |
console.log('listen 3000 port'); | |
}); | |
serial.on('open', function () { | |
console.log('open'); | |
}); | |
serial.on('data', function (data) { | |
//0.52秒に一度送られてくる超音波センサの値をcmになおして表示する。 | |
var distanceString = data.toString(); | |
var distanceNum = parseFloat(distanceString); | |
if (distanceNum == 65535 || distanceNum == 0) { //たまに超音波センサが固まって65535や0を返すときがある…マイコン側で対策。 | |
distanceString = "Distance: " + "--- cm"; | |
} else { | |
distanceNum = distanceNum * 0.187; //11サイクル、4MHz、音速340m/s | |
distanceString = "Distance: " + distanceNum.toFixed(0) + " cm"; | |
} | |
//動作確認用に受信したらドットを点滅させる。 | |
statusStr = (statusStr == ".") ? "" : "."; | |
distanceString += statusStr; | |
io.emit('distance', distanceString); | |
}); | |
//コマンドを受信したら、シリアルポートに書き込む | |
io.on('connection', function (socket) { | |
socket.on('sendcommand', function (msg) { | |
console.log(msg); | |
serial.write(msg, function (err, results) { | |
}); | |
io.emit('sendedcommand', msg); //他のブラウザとの同期のためにコマンドをemitする | |
}); | |
}); |