1.きっかけはこのツイート
気になるツイートを見かけました。
M5Stickを使って、小さな4脚ロボットを動かしているのですが、それぞれ1関節だけの新シンプルなロボット。#M5StickC— Google Homer (@google_homer_) August 22, 2019
4足歩行ロボ、ESP32Servo×4台。十分ちっちゃいんだけど、M5StickCがmicroサーボより小さいので相対で大きく見えてしまう。 pic.twitter.com/qe1Y0rpLQH
一本一本の足を見ると、サーボホーンがその場で往復運動をしているだけなので、ロボットはどちらへも進めない様な気がしますが、上手に歩いています。
どうして歩けるのか?
いくつか仮説を立てました。
- 足の裏に摩擦力を偏向させる「何か」が貼り付けられている
- ロボットの重心がずれていて一方方向の摩擦が強くなり前進できる
- 歩くピッチを前後でアンバランスさせることで2と同様の効果を出している
良く観察してみても足の裏になにか細工してる様子は無いし、なによりも面白くないので仮説1は却下。仮説2も最初に目が行くところですが、では前進しか出来ない構造なのか?だとしたら面白くないですね。そしてさらに良く観察すると、前足の方が後足よりも足の動作角度が広く、上下動も激しい。これなら足ごとに制御を変える事で前後進はもとより旋回運動もできそう。と言う事で本命は仮説3とあいなります。
2.仮説をたてたら即検証
なんとなく仮説3がいちばんもっともらしいな、とは思いますが試してみなければわからないので実際に作って検証してみました。
結果は、動画の通り歩く事が出来ました。動画では、前進10歩、更新10歩、左旋回前進10歩、右旋回前進10歩をループしています。
Twitterの動画はSG-90らしきサーボモーター4個の上にM5StickCを載せて制御していますがあいにくM5StickCは持ち合わせが無かったので代わりに以下の部品構成で製作しました。
結果は、動画の通り歩く事が出来ました。動画では、前進10歩、更新10歩、左旋回前進10歩、右旋回前進10歩をループしています。
3.構造
検証内容の説明の前に製作したロボットの構造と回路について。Twitterの動画はSG-90らしきサーボモーター4個の上にM5StickCを載せて制御していますがあいにくM5StickCは持ち合わせが無かったので代わりに以下の部品構成で製作しました。
- SG-92R×4台(SG-90の高トルク版。動作速度はほぼ同じ)
- 3tアクリル板(適当サイズ)
- スイッチ付き電池ボックス、単3×4本
- ユニバーサル基板(適当サイズ)
- Arduino nano(ユニバーサル基板にてサーボと接続)
製作方法もとても簡略化しています。まずアクリル板にSG-92Rを両面テープで固定。その上に電池ボックスを両面テープで固定して基本構造は完成です。
上手く取り付ければ、アクリル板も不要で電池ボックスにサーボ
上手く取り付ければ、アクリル板も不要で電池ボックスにサーボ
制御はArduino nanoで行いますが、入力ピン取り出しの為にユニバーサル基板にピンソケットを立てています。基板上には、Arduino接続用の他、電池から電源入力のための2ピンのピンソケット×1、サーボ出力の為の3ピンのピンヘッダー×4を取り付けました。
ユニバーサル基板は電池ボックスの上にM1ネジで取り付けました。
堂々と載せてはいますが、あまりやってはいけない回路になっています。電源に単三エネループ×4を使用していますが、Arduino NANOの外部電源供給はVinへ7V~12Vです。
電源はエネループ直列4本で理論値4.8V、実測5.6Vでした。Vinに入れるには電圧不足ですので、サーボ駆動用電源を共有して5V出力ピンに直結しています。
NANOは駆動電圧5Vなのでこれでもぎりぎり動作していますが、Vinとは異なり保護回路が入っていないため、ボードを破損する可能性があります。
①基本条件
・各足は、定めたピッチ(角度)に従って、一定のタイミングで往復運動する。
・ピッチは、中点(0°)を中心に対して±の幅をピッチ幅(θ°)として与える。
・右前足と左後足は同位相。左前足と右後足は、右前足と逆位相。
②前進
・左右前足のピッチ幅65°
・左右後足のピッチ幅30°
③後進
・左右前足のピッチ幅30°
・左右後足のピッチ幅65°
④左旋回前進
・右前足のピッチ幅65°
・左前足のピッチ幅50°
・右後足のピッチ幅45°
・左後足のピッチ幅30°
➄右旋回前進
・右前足のピッチ幅50°
・左前足のピッチ幅65°
・右後足のピッチ幅30°
・左後足のピッチ幅45°
※基本動作パターンは上記の通りですが、工作精度やサーボの動作精度などのバランスに合わせて微調整したパラメータをセットしています。概ね、前進力を高めたいサーボのピッチ幅を大きくとる事で調整しています。
仮説1でも歩行は可能と思われますが、検証により、その他の方法でも歩く事が出来ると証明できました。
仮説2についてはすべての足のピッチを揃え、荷重バランスのみ変更してもあまり安定した歩行が出来なかったため、却下しました。理想条件では、前後の足で荷重バランスを変えたとしても一本の足が生み出す前進力と後進力がバランスして、進むことにはならないはずです。
仮説3についてはいちばんもっともらしいかとも思いましたが、重心位置の変化だけでは、仮説2と同様に前進力は得られません。
そこで考えたのが仮説4です。
仮説4とは、前後の足のピッチ変更により、ボディに傾きが発生。足の中立位置が傾きます。すると、前進力と後進力の発生タイミングがずれて、前進→停止→前進→停止というループで前進している。という仮説です。
考察してみて意外だったのは、力のベクトル(前進力と後進力)のバランスのみに着目して、なぜ進めるのか?と感じていたのですが、それぞれのタイミングがわずかにずれるだけで本体の変位が変わる(前に進む)ということでした。当然と言えば当然なのですが意外と盲点でした。
まだ、詳細な検証の余地はありますが、ほぼ間違いなさそうな仮説が出たのでとりあえずこの実験は終了です。一応スケッチも載せておきます。
//サーボを宣言。servo0が右前足(FR)、1が左前(FL)、2が右後(RR)、3が左後
Servo servo0;
Servo servo1;
Servo servo2;
Servo servo3;
//出力ピン設定
const int outpin0 = 10; //右前(FR)
const int outpin1 = 9; //左前(FF)
const int outpin2 = 6; //右後(RR)
const int outpin3 = 5; //左後(RL)
//サーボ中立位置の調整。任意の数値を入れて、中立時にセンターが合うように調整
const int servo0Shift = -10;
const int servo1Shift = -6;
const int servo2Shift = -10;
const int servo3Shift = -8;
void setup() {
//出力ピンにサーボをアタッチ
servo0.attach(outpin0);
servo1.attach(outpin1);
servo2.attach(outpin2);
servo3.attach(outpin3);
Serial.begin(9600);
//電源オンで、中立位置
servo0.write(90 + servo0Shift);
servo1.write(90 + servo1Shift);
servo2.write(90 + servo2Shift);
servo3.write(90 + servo3Shift);
delay(2000);
}
void loop() {
static int count = 0;
static int FR = 90;
static int FL = 90;
static int RR = 90;
static int RL = 90;
//forward 10歩前進
if (count / 10 == 0) {
FR = 65;
FL = 65;
RR = 30;
RL = 30;
}
//back 10歩後進
else if (count / 10 == 1 ){
FR = 30;
FL = 30;
RR = 66;
RL = 65;
}
//turn left 10歩左旋回
else if (count / 10 == 2 ){
FR = 65;
FL = 55;
RR = 45;
RL = 30;
}
//turn right 10歩右旋回
else if (count / 10 == 3 ){
FR = 50;
FL = 65;
RR = 30;
RL = 45;
}
count = count + 1;
if (count == 40){
count = 0;
}
servo0.write(90 + FR + servo0Shift);
servo1.write(90 + FL + servo1Shift);
servo2.write(90 - RR + servo2Shift);
servo3.write(90 - RL + servo3Shift);
delay(300);
servo0.write(90 - FR + servo0Shift);
servo1.write(90 - FL + servo1Shift);
servo2.write(90 + RR + servo2Shift);
servo3.write(90 + RL + servo3Shift);
delay(300);
}
4.回路
今回使用したArduino NANOのピンアウトと回路は次の通り。Arduino NANO Pinout |
よつあしロボットMINIの回路図 |
電源はエネループ直列4本で理論値4.8V、実測5.6Vでした。Vinに入れるには電圧不足ですので、サーボ駆動用電源を共有して5V出力ピンに直結しています。
NANOは駆動電圧5Vなのでこれでもぎりぎり動作していますが、Vinとは異なり保護回路が入っていないため、ボードを破損する可能性があります。
5.動作パターン
今回、仮説3を元に試行錯誤しながら動作パターンをを作成しました。①基本条件
・各足は、定めたピッチ(角度)に従って、一定のタイミングで往復運動する。
・ピッチは、中点(0°)を中心に対して±の幅をピッチ幅(θ°)として与える。
・右前足と左後足は同位相。左前足と右後足は、右前足と逆位相。
②前進
・左右前足のピッチ幅65°
・左右後足のピッチ幅30°
③後進
・左右前足のピッチ幅30°
・左右後足のピッチ幅65°
④左旋回前進
・右前足のピッチ幅65°
・左前足のピッチ幅50°
・右後足のピッチ幅45°
・左後足のピッチ幅30°
➄右旋回前進
・右前足のピッチ幅50°
・左前足のピッチ幅65°
・右後足のピッチ幅30°
・左後足のピッチ幅45°
※基本動作パターンは上記の通りですが、工作精度やサーボの動作精度などのバランスに合わせて微調整したパラメータをセットしています。概ね、前進力を高めたいサーボのピッチ幅を大きくとる事で調整しています。
6.考察
ロボット組立前はどうして進むことが出来るのか仮説を三つ立てていましたが、いずれも説得力に欠けるものでした。仮説1でも歩行は可能と思われますが、検証により、その他の方法でも歩く事が出来ると証明できました。
仮説2についてはすべての足のピッチを揃え、荷重バランスのみ変更してもあまり安定した歩行が出来なかったため、却下しました。理想条件では、前後の足で荷重バランスを変えたとしても一本の足が生み出す前進力と後進力がバランスして、進むことにはならないはずです。
一本の足の動きに注目した場合、歩行動作は中立状態の①を原点とし、 ①→②→①→③→①という動作の繰り返しとなる。②→①→③の動作と ③→①→②の動作が相殺し合って、どちらかへ進むことは出来ない。 左右の足の動きの合成力を考えた場合、右足の②→①→③の動作と、 左足の③→①→②の動作が同じタイミングで発生し、力を相殺する。 |
そこで考えたのが仮説4です。
仮説4とは、前後の足のピッチ変更により、ボディに傾きが発生。足の中立位置が傾きます。すると、前進力と後進力の発生タイミングがずれて、前進→停止→前進→停止というループで前進している。という仮説です。
軸が傾く事により、②→①の間に前進力、①→②の間に後進力が発生する。 ①→③の間は、反対サイドの足が接地し、こちらサイドの足は中に浮くため 前進力は発生しない。右足が②→①に動くと同時に左足は③→①に動くが、 このタイミングでは右足のみが力を発生し、前進する。次に右足が①→③に 動く際に、左足が①→②に動き、左足のみが力を発生、前進の慣性力を相殺 して停止する。 |
考察してみて意外だったのは、力のベクトル(前進力と後進力)のバランスのみに着目して、なぜ進めるのか?と感じていたのですが、それぞれのタイミングがわずかにずれるだけで本体の変位が変わる(前に進む)ということでした。当然と言えば当然なのですが意外と盲点でした。
まだ、詳細な検証の余地はありますが、ほぼ間違いなさそうな仮説が出たのでとりあえずこの実験は終了です。一応スケッチも載せておきます。
7.スケッチ
#include <Servo.h>//サーボを宣言。servo0が右前足(FR)、1が左前(FL)、2が右後(RR)、3が左後
Servo servo0;
Servo servo1;
Servo servo2;
Servo servo3;
//出力ピン設定
const int outpin0 = 10; //右前(FR)
const int outpin1 = 9; //左前(FF)
const int outpin2 = 6; //右後(RR)
const int outpin3 = 5; //左後(RL)
//サーボ中立位置の調整。任意の数値を入れて、中立時にセンターが合うように調整
const int servo0Shift = -10;
const int servo1Shift = -6;
const int servo2Shift = -10;
const int servo3Shift = -8;
void setup() {
//出力ピンにサーボをアタッチ
servo0.attach(outpin0);
servo1.attach(outpin1);
servo2.attach(outpin2);
servo3.attach(outpin3);
Serial.begin(9600);
//電源オンで、中立位置
servo0.write(90 + servo0Shift);
servo1.write(90 + servo1Shift);
servo2.write(90 + servo2Shift);
servo3.write(90 + servo3Shift);
delay(2000);
}
void loop() {
static int count = 0;
static int FR = 90;
static int FL = 90;
static int RR = 90;
static int RL = 90;
//forward 10歩前進
if (count / 10 == 0) {
FR = 65;
FL = 65;
RR = 30;
RL = 30;
}
//back 10歩後進
else if (count / 10 == 1 ){
FR = 30;
FL = 30;
RR = 66;
RL = 65;
}
//turn left 10歩左旋回
else if (count / 10 == 2 ){
FR = 65;
FL = 55;
RR = 45;
RL = 30;
}
//turn right 10歩右旋回
else if (count / 10 == 3 ){
FR = 50;
FL = 65;
RR = 30;
RL = 45;
}
count = count + 1;
if (count == 40){
count = 0;
}
servo0.write(90 + FR + servo0Shift);
servo1.write(90 + FL + servo1Shift);
servo2.write(90 - RR + servo2Shift);
servo3.write(90 - RL + servo3Shift);
delay(300);
servo0.write(90 - FR + servo0Shift);
servo1.write(90 - FL + servo1Shift);
servo2.write(90 + RR + servo2Shift);
servo3.write(90 + RL + servo3Shift);
delay(300);
}