ダンボールで工作

12082601
ダンボールを短冊状に切って
12082602
12mm厚になるように重ねて
12082603
白色のテープを巻いて
12082604
床に並べる

参考:http://monoist.atmarkit.co.jp/mn/articles/1208/08/news002_4.html

夏休みの成果

120817
強度UPを狙う新しいカメラユニットの支柱ができた。4g位重くなってしまった。
操舵の影響でカメラが揺れるのを防ぐためには、思ってた以上に捩れ剛性が必要なようだ。

走行速度が向上すると共に
初期の構成だとカメラが揺れるのが目で見て分かるようになってきた。
その後、支持棒の間隔を22mmから42mmに広げることで目視では振動は無くなったが、
ログを見ると偶にコーナ旋回中にライントレースが振動的になることがあった。
BOSSの助言で支持棒をダンボールで補強してやるとログ上でも振動が収まり、コーナ旋回中の暴れも減ったため、その仕様でRMCRには参加した
しかし、構造的に弱いようなので今回の作成にいたる。
結果、手で触っても剛性があがったようなので暫くは安心してよいかな

集光レンズ

あと5cm先を見るために、カメラの取り付け角度を変更する
これまで0.9程度だったSSMレバー比が1.2位になる。
で、
確認用のコースでライン検出を確認するとクロスラインを検出できない。
照明用LEDの取り付け角度や距離が変わり反射が小さくなったせいか。
RMCR参加時の照明の組み合わせは
秋月の1WパワーLEDレンズホルダをつけた物だった。
最初はLEDだけで使用し、明るさを補うため反射板を自作して試したりしたが、結局レンズが一番結果が良かった。

このレンズホルダに標準で入っているレンズは、おそらくOSOLRA2045Mでデータシートでの照射角度は45度。
なのでさらに集光するために照射角度30度のOSOLRB2030Mに変更する。
結果としてクロスラインが見えるようになった。ただ照射範囲が狭くなり明るさにムラが出るので、LEDをあと1つ追加したほうが良いかも。

ちなみに15度品のOSOLRA2015Mも試したが、これは30度品と集光の変化が無いように見える。

目的は路面を明るく照らすことであって、LED照明を作ることではないので、
これ以上の明るさを求めるなら、下手に試行錯誤するよりも
市販の光学的に調整されたフラッシュライトを分解して使うべきだろうな。

やっぱり白色パワーLEDか

120814
モノクロカメラ素子の感度のピークが赤外近くにあるなら、
赤色のフラッシュを焚いて、カメラにローパスフィルタつければ、
外乱光の影響を抑えることができるのでは?
ということを大雑把に試してみた。
波長580nm以下の光をカットしてくれるシャープカットフィルタSC58(見た目はカラーセロハン)と
波長660nmの超高輝度LEDのH-3000L(3000mcd)を組み合わせてみた。
カメラで撮影すると、フィルタ有り無しでの明るさの変化はほぼなく、外乱光の影響も小さくなりそう。
しかし、全体的に暗い。
4灯で0.15W位しかないため、光量がまるで足りていない。
というか660nm付近のLEDはあまり発光効率が良くないみたい。
現在の照明と同じ光量にするためには沢山のLEDが必要となり、重くなるので照明には使えなさそう。

照明を焚く理由は、ハレーション対策や坂の下等の一部暗い所で画が暗くなることの対策もあるけれど、
露光時間を短くしてブレた画を作らないようにすること。
常にロボットは動いているので露光時間が長いと、
トレースラインやクロスラインがボヤケて白色がどんどん暗くなり、コントラストが悪くなる。

露光時間が長すぎると
クロスラインを見落とすだけでなく、S時コーナの切り替えしやクランクや
車線変更の復帰時のようなところでもコースを見失ってしまう。

M64282FPまとめ

①中古のポケットカメラを買ってくる(amazonで1円~)
②特殊ねじの頭をドリルで壊す
IMG_0737
③M64282FPとレンズのついたモジュールが出てくる
IMG_0746
④各信号線を確認して
IMG_0752
⑤Arduinoにつなぐ
IMG_0750
⑥プログラムを書く
#define voutPin 0
#define readPin 2
#define xckPin 3
#define resetPin 4
#define loadPin 5
#define sinPin 6
#define startPin 7

#define reg0 0x00
#define reg1 0x0F //ゲイン
#define reg2 0x05 //C1 露光時間
#define reg3 0x00 //C0 露光時間
#define reg4 0x01
#define reg5 0x00
#define reg6 0x01
#define reg7 0x07

#define Xck_H digitalWrite(xckPin,HIGH)
#define Xck_L digitalWrite(xckPin,LOW)

unsigned char data[256];

// the setup routine runs once when you press reset:
void setup() {
// initialize serial communication at 9600 bits per second:
Serial.begin(9600);

pinMode(readPin, INPUT);
pinMode(xckPin, OUTPUT);
pinMode(resetPin, OUTPUT);
pinMode(loadPin, OUTPUT);
pinMode(sinPin, OUTPUT);
pinMode(startPin, OUTPUT);

}

// the loop routine runs over and over again forever:
void loop() {
char buf;
int adcnt;
int datacnt;
int i;

digitalWrite(resetPin,LOW);//RESET -> L
Xck_H;
Xck_L;
Xck_H;
Xck_L;
digitalWrite(resetPin,HIGH);//RESET -> H リセット解除
Xck_H;
Xck_L;

//レジスタ設定
setReg(2,reg2);
setReg(3,reg3);
setReg(1,reg1);
setReg(0,reg0);
setReg(4,reg4);
setReg(5,reg5);
setReg(6,reg6);
setReg(7,reg7);

Xck_H;
Xck_L;
digitalWrite(startPin,HIGH);//スタートH カメラスタート
Xck_H;
digitalWrite(startPin,LOW);//スタートL
Xck_L;
Xck_H;

while(digitalRead(readPin)==LOW){//READシグナル待
Xck_L;
Xck_H;
}

adcnt=0;
datacnt=0;

//今回は8列8行毎に32×32画素を取得する
while(datacnt<255){
if((adcnt&0x0070)==0x0000){//8列中1列データ取得
data[datacnt]=(analogRead(voutPin)/4); //ADの最大値1024を8bitに圧縮
datacnt=datacnt+1;
}
adcnt=adcnt+1;
Xck_L; Xck_H;
Xck_L; Xck_H;
Xck_L; Xck_H;
Xck_L; Xck_H;
Xck_L; Xck_H;
Xck_L; Xck_H;
Xck_L; Xck_H;
Xck_L; Xck_H;
}

//シリアルモニタに画像データを表示する
for(i=0;i<256;i++){
if(i%16==0){Serial.println(" ");}
if(data[i]<100){Serial.print(" ");}
if(data[i]<10){Serial.print(" ");}
Serial.print(data[i], DEC);
Serial.print(" ");
}
Serial.println(" ");

while(1){}
}

void setReg( unsigned char adr, unsigned char data )
{
//アドレス転送(3bit)
if((adr&0x04)==0x04){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((adr&0x02)==0x02){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((adr&0x01)==0x01){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;

//データ転送(8bit)
if((data&0x80)==0x80){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x40)==0x40){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x20)==0x20){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x10)==0x10){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x08)==0x08){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x04)==0x04){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x02)==0x02){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H; Xck_L;
if((data&0x01)==0x01){digitalWrite(sinPin,HIGH);}else{digitalWrite(sinPin,LOW);}
Xck_H;
digitalWrite(loadPin,HIGH); //LOADピン→H
digitalWrite(sinPin,LOW);
Xck_L;
digitalWrite(loadPin,LOW); //LOADピン→L
}

カメラの感度調整は殆ど露光時間で行う。
ゲインで弄ると2値化処理しているような画になる。

フレームレートは露光時間とデータ転送時間できまる
照明を明るくして露光時間を減らした上で、
Xckのクロックを上げて、AD変換速度も上げる。(がじぇるねを使う)
さらに、
128×128画素も不要ならばデータを読み飛ばしてAD変換の時間を削る。
画の後半が不要ならば、データの始めの方(写真の上の方)だけを取得して
リセットをかける。捨てた後半のデータ転送時間が節約できる
これで、H8-3048で37fps位にはなる。

参考
http://www.seattlerobotics.org/encoder/200205/gbcam.html
http://www2.plala.or.jp/k_y_yoshino/w6/vision.html
http://mieng.net/miu/index.php?main_page=product_info&products_id=18
http://embedded754.blog6.fc2.com/

MCR-VCどうやって作るか

画処理ロボットは
Takumiさんが見つけたモジュールを
大湯さんの手法で動かして、
滝田研究室の制御法でライントレースしている。
JMCR2004で既にtakumiさんや滝田教授がやってたことである。

○カメラ制御
カメラへ供給するクロックや信号の幅は無視して、
汎用IOをパコパコ動かして制御している。
このやり方はカメラの種類は違うけれど、大湯さんのゲームボーイカメラ(M64282)用コードを元にしている。
Takumiさん曰く、アセンブラで書くともっとサンプリング周波数を上げることは可能なのだけど、
スキルが無いので、H8→SHにしてサンプリング周波数を向上させている

○画データからのラインの検出
カメラデータ中のあるラインを左から右方向に差分して行き、
その差分値の最大値と最小値の間にラインがあると判断する。

これは、滝田研究室の論文
超小型1kHzスマートカメラを用いたSSM軌道誘導車両の制御 : 動吸振器による安定化
を参考に作成

○ライントレース制御
2重ループのカスケード制御で
外のループで
ライン中心点の位置と現在の操舵角度から目標操舵角度を求める
このループの速度はカメラのサンプリング周波数に影響される
内のループで
目標操舵角度と操舵角度が一致するように制御している
これは、滝田研究室の論文
1kHzスマートカメラ搭載SSM軌道誘導車両の高速化 : 操舵比とレバー比可変によるドリフト抑制
を参考にしたのだけど、間違って解釈していたようで形が違うことがわかった。

○駆動系
いつものメカにいつもの制御。

というわけで、画処理ロボットは
先人のネタを再構築して、CPUパワーと駆動系性能によるゴリ押しで走っています。

モータドライブ回路

120812
件のモータドライブ回路の構成を公開する
A3941+IRF8915の構成で、PWM周期40kHzで駆動させている。

allegroのA3941はフルブリッジFETドライバ。
PWMと回線方向とフリーの3本の信号を入力するだけで、
Nch構成のHブリッジを動かしてくれる便利なIC。
デットタイムは外付け抵抗で調整可能。

IRF8915はNchFET2個入りで、
片側18.3mΩで8.9A流せる。
ゲート容量も小さいのでスイッチング速度も上げれる。

リクエストがあれば定数も書きます。
リクエストあったので定数も公開
120802
(A3941データシートより)
・RESET端子はマイコンの電源と同じにする。
・FF1とFF2端子は、GNDに落としても良いかもしれない(未検証)
・FREEは使ってないので、動作未検証(→TypeS等のFREEと挙動が異なる@2015年2月)

////////////
追記 PWM40kHz付近でのモータ両端電圧波形
BREAKモード(SR=H)
15020702
FREEモード(SR=L)
15020701
PWMがLの区間での電圧がマイナス方向に触れている。
内部のダイオードの電圧降下分か?
これにより同一duty時にはFREEの方がモータの回転速度は遅い

/////////////
追記
FREEの動作について
モータドライブ基板TypeS等のFREEはPWMのOFF時間はモータ端子が開放されれ逆起電流は流れないが、このモータドライバでは電流が流れるので振る舞いが異なる

/////////////
PWMOFF時間中にFETのボディダイオード分の逆電圧(0.7V位?)が掛かって回転が阻害されるのならば、そのFETに並列にVfの小さいダイオードを付ければ改善されるはず。
ということでショットキーを付けてみる
15021402
OFF区間中の逆電圧が小さくなり、回転数も上がった。
FREEモードを使うのは正転時だけだから部品追加は1個ですむ。
ただ、スイッチング時のスパイクが増えたのは気持ち悪い。

第3回RMCR

Tsubameさんと共に会場入り。
全国から好き物が集まる大会は本当に面白い。
コースも直射日光も入らず、画処理でも走れる良い環境。

予選はフリー走行で本当に助かった。今年も予選落ちする所だった。
連続S時でトレースを失敗してのコースアウトは仕方ないが、
バグでコース上で立ち往生してしまうのは本当に困った。

決勝トーナメント
予選通過タイムが悪いため記念走行だったのだけど、
s技研さんがまさかのコースアウト。タナボタでベスト16入り。

上位のタイムは素晴らしいの一言。ランサーは二冠おめでとうございます。

(一部に?)人気だったCMAさんのロボット
特徴的なセンサバーレスのライントレースとバッテリ2本による駆動。
さらに走行中の駆動音が聞こえない。

みなさんお疲れ様でした。
楽しい大会ありがとうございました。
画処理ロボットで防衛大超えたぞ。ドヤッ。


(RenesasMCR1 配信より)

こつこつ

120715
・恒例の搬送箱を作る。
センサバーが無いと長さが短くなってよい。
高さ方向はカメラユニットごと取り外して低く抑える。

・レバー比(センサアーム長さとホイルベースの比)が小さいと走らない。
結局、クランク立ち上がり時の起動は改善できず。
ちなみに車線変更も危ない。
あと5cm先を見たい。

ソフトでカメラの注視点を変えれば先は見れるのだが
カメラと路面との角度が浅くなり、照明の効果が薄れてしまう。
現状でも坂の頂上での7度の角度の変化で不安定になる。
坂区間でのみ注視点を変える制御は、そのうち検討。

こつこつ


コマ送りで見るとクランクの立ち上がりで前輪が外側白線を踏んでいる
マージン無し。要再調整

カメラ誘導は想像以上に遠くを見ることができない(遠距離の画像が使いにくい)
そのため、実際の操舵輪-ラインセンサまでの距離はかなり短くなってしまう。
クランクや車線変更では、操舵する起点(ライン途切れ、直角)の検知も遅れる

日程の都合上の大会までの調整可能日はあと2日。
どうにかなるか、どうにかせねば

////////////////////////////////////////////////////////////////////////////////////
if(EncoderTotal-tmpEncoder>455){
これもたまに上手く動かない
if((EncoderTotal-tmpEncoder)>455){
括弧をつけると動く