HOME > 4脚ロボットの製作

 4脚ロボットの製作 

多脚ロボット製作中. 多脚ロボットを作りたいという学生がいて,ようやく1本できました.
記念写真↓
CIMG9388.JPG
完成が楽しみ.

学生のN君奮闘中.4脚できました.
CIMG9399.JPG
早速,動かしてみました. センターがずれてるので調整しなおして胴体に結合します. 制御はArduinoの2-13番のデジタルピンでサーボ信号をPWMで出力 しています.動画で一部は動いてませんが,信号の単芯線の被覆を剥い た長さが短くて接触不良.それぞれ動くことは確認済み.
その動画→ 4脚ロボット製作中

4脚ロボット製作中,プログラムで動かせるようにした.
Arduinoを使って制御ソフト作成中. 配列にモーションを定義して順次呼び出して動かせるようにプログラムしました. 胴体に組み上げたら,後は地道にモーションを作れば歩くはず.
その動画→ 4脚ロボット製作中,プログラムで動かせるようにした.

ここまでのスケッチ

#include < Servo.h> 

int o[12]={0,0,0,0,0,0,0,0,0,0,0,0};    // サーボのニュートラルのオフセット
int r[12]={0,0,0,0,0,0,0,0,0,0,0,0};    // サーボの制御入力(例えばジャイロ補正など)

// 形態定義
// 1脚3関節(第1,第2,第3)×4(1:右前,2:左前,3:右後,4:左後)+変形時間
// 13個まで形態定義可能
int form[13][13]={
  { 90, 90, 90, 90, 90, 90, 90, 90, 90, 90, 90, 90,150},  // 基本形態,ニュートラル位置
  {120, 90, 90, 90, 90, 90, 90, 90, 90, 90, 90, 90,150},
  { 90,120, 90, 90, 90, 90, 90, 90, 90, 90, 90, 90,150},
  { 90, 90,120, 90, 90, 90, 90, 90, 90, 90, 90, 90,150},
  { 90, 90, 90,120, 90, 90, 90, 90, 90, 90, 90, 90,150},
  { 90, 90, 90, 90,120, 90, 90, 90, 90, 90, 90, 90,150},
  { 90, 90, 90, 90, 90,120, 90, 90, 90, 90, 90, 90,150},
  { 90, 90, 90, 90, 90, 90,120, 90, 90, 90, 90, 90,150},
  { 90, 90, 90, 90, 90, 90, 90,120, 90, 90, 90, 90,150},
  { 90, 90, 90, 90, 90, 90, 90, 90,120, 90, 90, 90,150},
  { 90, 90, 90, 90, 90, 90, 90, 90, 90,120, 90, 90,150},
  { 90, 90, 90, 90, 90, 90, 90, 90, 90, 90,120, 90,150},
  { 90, 90, 90, 90, 90, 90, 90, 90, 90, 90, 90,120,150}
};

// モーション定義
// 1モーションについて最高10個の形態変形で作る.
// モーションは最高5個まで定義可能.
int motion[5][10]={
  { 0,99,99,99,99,99,99,99,99,99},
  { 1, 2, 3, 0,99,99,99,99,99,99},
  { 4, 5, 6, 0,99,99,99,99,99,99},
  { 7, 8, 9, 0,99,99,99,99,99,99},
  {10,11,12, 0,99,99,99,99,99,99}
};

Servo leg11;  
Servo leg12;           
Servo leg13;  
Servo leg21;  
Servo leg22;           
Servo leg23;  
Servo leg31;  
Servo leg32;           
Servo leg33;  
Servo leg41;  
Servo leg42;           
Servo leg43;  
 
 
void doMotion(int n){
  for(int i=0; i<10; i++){
    if (motion[n][i]!=99) setForm(motion[n][i]);    // 形態変形,99の時はモーション終了
  }
}

void setForm(int n){
    leg11.write(form[n][0]+o[0]+r[0]); leg12.write(form[n][1]+o[1]+r[1]); leg13.write(form[n][2]+o[2]+r[2]);           
    leg21.write(form[n][3]+o[3]+r[3]); leg22.write(form[n][4]+o[4]+r[4]); leg23.write(form[n][5]+o[5]+r[5]);   
    leg31.write(form[n][6]+o[6]+r[6]); leg32.write(form[n][7]+o[7]+r[7]); leg33.write(form[n][8]+o[8]+r[8]);   
    leg41.write(form[n][9]+o[9]+r[9]); leg42.write(form[n][10]+o[10]+r[10]); leg43.write(form[n][11]+o[11]+r[11]);  
    delay(form[n][12]);
}

void setup() 
{ 
  leg11.attach(2);  
  leg12.attach(3);  
  leg13.attach(4);  
  leg21.attach(5);  
  leg22.attach(6);  
  leg23.attach(7);
  leg31.attach(8);  
  leg32.attach(9);  
  leg33.attach(10);
  leg41.attach(11);  
  leg42.attach(12);  
  leg43.attach(13);
} 
 
void loop() 
{ 
  doMotion(1);  // モーション1を実行
  doMotion(2);  // モーション2を実行
  doMotion(3);  // モーション3を実行
  doMotion(4);  // モーション4を実行
}

4脚ロボット,胴体ができて脚がついた

ちょっとシンガポールに1週間いってましたので更新がなかったですが, N君が頑張ってます. 胴体(といってもアルミ板2枚)ができて形が見えてきました. Arduino上にちょっと回路をのせてサーボを接続するだけでハードは完成. ソフトのひな形もできてるので,モーション作れば歩きます. あとは,どんなセンサを積んでどんな目的で自律歩行させるか.
CIMG9717.JPG
4脚ロボット,動き始めました.
Arduinoのバニラシールドを使って配線. センサ等を載せるスペースは十分空いてます. サーボを動かす時に電流を食ってマイコンが誤動作しやすいので,電源は2系統 に分けました.1つはArduino専用でDCジャックからリポ2セルで供給予定, 今はUSBから供給しながら開発.もう一つはサーボ専用にニッケル水素5本. 本体裏側に電池ケースを貼り付けています.
CIMG9722.JPG
裏面の電池搭載4本と2本の電池ケースで1本分はショート↓
CIMG9725.JPG
前にリストを載せたサーボの順に少しずつ動かすサンプルプログラムを実行して みました.ピクピク動いてますがここまでできたら後は時間の問題で歩き出します.
動画はこちら→ 4脚ロボット・サーボテスト

4脚ロボット,歩き始めました

まだぎこちないですが,歩行モーションを一つ作ってみました. 重心移動は考慮しておらず,交互に足を出すだけです. 前足はあがっていますが後ろ足がうまく上がっていません. 次は重心移動をしながら足を1本づつ上げ下げして歩かせてみます.
CIMG9986-2.jpg
動画→ 4脚ロボット,歩き始めました.

4脚ロボットをBluetoothで無線操縦

Bluetoothで無線操縦と、CUIモーションエディタも完成. 今度のオープンキャンパスに間に合わせようと思って,急ピッチで残りの作業. Bluetoothモジュールをのせて無線操縦可能にしました. PCからキーボード操作でも動かせるし,スマホのアプリからも動かせます. スマホ(Android)のアプリは以前作った,ラジコンカーを動かすやつ そのままで使えます.
(コマンドはアルファベット(記号・数字)を1文字送るだけ)
CIMG0115-2.jpg
モーションエディタはCUIで作りました.ターミナルソフトで接続してコマンド を送るだけで,制御兼モーションエディタになってます.すべてアルファベット (記号・数字)をコマンドに割り当てて,モーション作成,保存, モーション実行までできます.後はモーション作るだけ.

[コマンド一覧]
1-9:ポーズ番号選択
-:ポーズを-10
^:ポーズを+10
w:0番脚の第1関節を+5度
q:0番脚の第1関節を+5度
s:1番脚の第2関節を+5度
a:1番脚の第2関節を+5度
・・・4番脚の第3関節まで同様(r,e,f,d,v,c,y,t,h,g,n,b,i,u,k,j,,m)・・・
o:ポーズ遷移時間を-50ms
p:ポーズ遷移時間を+50ms
N:ポーズを次の番号にコピー
B:ポーズを前の番号にコピー

SHIFT+1-9:モーション番号選択(モーション実行)
A:モーションに現在のポーズを追加
D:モーションからポーズを1つ削除

P:ポーズとモーション一覧覧表示
L:ファイルからロード
S:ファイル保存
W:EEPROMにポーズとモーションを書込
R:EEPROMからポーズとモーションを書込
C:ポーズをニュートラル位置,モーションをクリア

電源を改良

サーボの電圧が上限6Vだったけど6Vのレギュレータが無かったのでニッケル水素 単3を5本で動かしていたのですが,6Vレギュレータを注文・到着したので, 電源回路を改良. 静止時で0.8Aの電流が流れており,動作時は電流が1-2A流れてた ので,レギュレータを3個並列. 発熱が気になったので,この写真を取った後に放熱板をつけました. CIMG0640.JPG CIMG0644.JPG PCとBluetoothで接続してキーボードで動かせます.動作時のポーズと モーションの変化もシリアルターミナルに表示されます. 動画はこちら→ 4脚ロボット完成

スケッチ


// 4脚ロボット制御ソフト兼モーションエディタ   葉山清輝(熊本高専)
//
// 2013. 9.30  v0: Arduinoで12チャンネル定義して独立に動かせることを確認
// 2013.10.01  v1: モーション定義して順次読みだして動かせるようにした
// 2013.11.28  v2: モーションエディタまで完成

#include < Servo.h> 
#include < EEPROM.h> 

// ポーズ定義
// 1脚3関節(第1,第2,第3)×4(1:右前,2:左前,3:右後,4:左後)+変形時間
// 13個まで形態定義可能
int form[30][13];

int o[12]={0,13,-9,3,-6,-5,0,-14,16,-7,2,2};  // サーボのニュートラルのオフセット  
int r[12]={0,0,0,0,0,0,0,0,0,0,0,0};          // サーボの制御入力(例えばジャイロ補正など)

// モーション定義
// 1モーションについて最高10個のポーズ変形で作る.
// モーションは最高5個まで定義可能.
int motion[10][11];
/*={
  { 0,99,99,99,99,99,99,99,99,99},
  { 1, 2, 3, 0,99,99,99,99,99,99},
  { 4, 5, 6, 0,99,99,99,99,99,99},
  { 7, 8, 9, 0,99,99,99,99,99,99},
  {10,11,12, 0,99,99,99,99,99,99}
};
*/

//unsigned char eeprombuf[512];

int mf=0;     // ポーズ作成中の番号
int mfi=0;     // ポーズ作成中のインデックス
int mfb=0;     // ポーズ作成番号のベース 
int mo=1;      // モーション番号

Servo leg11;  
Servo leg12;           
Servo leg13;  
Servo leg21;  
Servo leg22;           
Servo leg23;  
Servo leg31;  
Servo leg32;           
Servo leg33;  
Servo leg41;  
Servo leg42;           
Servo leg43;  

//-----------------------------------------------------------------------------------------------------
// モーション定義初期値セット
void motionReset(){
  int i,j;
  for(i=0;i<10;i++){
    motion[i][0]=0;
    for(j=0;j<11;j++) motion[i][j]=99; 
  } 
}

//-----------------------------------------------------------------------------------------------------
// ポーズ初期値セット
void formReset(){
  int i,j;
  for(i=0;i<30;i++){
    for(j=0;j<12;j++) form[i][j]=0; 
    form[i][12]=15;                  // ×10倍ミリ秒待つ.
  } 
}

//-----------------------------------------------------------------------------------------------------
// ポーズとモーション定義データの表示用シリアル出力
void dispOut(){
  int i,j;
  for(i=0;i<30;i++){
    Serial.print(" F:"); Serial.print(i); Serial.print(" ");
    for(j=0;j<13;j++){
      Serial.print(form[i][j]); if (j!=12) Serial.print(","); 
    }  
    Serial.println(); 
  }
  for(i=0;i<10;i++){
    Serial.print(" M:"); Serial.print(i); Serial.print(" ");
    for(j=0;j<11;j++){
      Serial.print(motion[i][j]); if (j!=10) Serial.print(","); 
    }  
    Serial.println(); 
  }
}

//-----------------------------------------------------------------------------------------------------
// 全データのファイル出力,シリアルターミナルでテキスト形式で保存
void saveAll(){
  int i,j;
  // ポーズ書き出し
  for(i=0;i<30;i++){
    for(j=0;j<13;j++){
      Serial.println(form[i][j]);
    }  
  }
  // モーション書き出し
  for(i=0;i<10;i++){
    for(j=0;j<11;j++){
      Serial.println(motion[i][j]);
    }  
  }
}

//-----------------------------------------------------------------------------------------------------
// 全データのファイル入力,シリアルターミナルからテキストファイルの転送(RawData形式)
void loadAll(){
  char str[10];
  int i,j;
  
  // ポーズ読出し
  for(i=0;i<30;i++){
    for(j=0;j<13;j++){
      recvStr(str);
      form[i][j]=atoi(str);
    }  
  }
  // モーション読出し
  for(i=0;i<10;i++){
    for(j=0;j<11;j++){
      recvStr(str);
      motion[i][j]=atoi(str);
    }  
  } 
}

//-----------------------------------------------------------------------------------------------------
// EEPROMからポーズデータの読出し
void formRead(){
  int i,j,k;
  k=0;
  // ポーズ読出し
  for(i=0;i<30;i++){
    for(j=0;j<13;j++){
      form[i][j]=EEPROM.read(k)-90;
      k++;
    }  
  }
  // モーション読出し
  for(i=0;i<10;i++){
    for(j=0;j<11;j++){
      motion[i][j]=EEPROM.read(k);
      k++;
    }  
  }
}

//-----------------------------------------------------------------------------------------------------
// EEPROMへポーズデータの書き出し
void formWrite(){
  int i,j,k;
  k=0;
  // ポーズ書き出し
  for(i=0;i<30;i++){
    for(j=0;j<13;j++){
      EEPROM.write(k,form[i][j]+90);
      k++;
    }  
  }
  // モーション書き出し
  for(i=0;i<10;i++){
    for(j=0;j<11;j++){
      EEPROM.write(k,motion[i][j]);
      k++;
    }  
  }
}

//-----------------------------------------------------------------------------------------------------
// 現在の状態表示
void dispState(){
    setForm(mf);
    Serial.print("M:"); Serial.print(mo);
    Serial.print(" F:"); Serial.print(mf); 
    Serial.print(" ");
    for (int i=0;i<13;i++) { Serial.print(form[mf][i]); if(i<12) Serial.print(","); }
    Serial.println();
}

//-----------------------------------------------------------------------------------------------------
// 文字列読み取り関数,改行がきたら区切る
void recvStr(char *buf)
{
  int i = 0;
  char c;
  while (1) {
    if (Serial.available()) {
      c = Serial.read(); // Serial.print(c);
      buf[i] = c;
      if (c == 13) break; 
      i++;
    }
  }
  buf[i] = '\0';  // \0: end of string
}

//-----------------------------------------------------------------------------------------------------
// 文字列読み取り関数,バッファ読み出しが終わったら区切る,1文字入力も可
void recvStr2(char *buf)
{
  int i = 0;
  char c;
  while (Serial.available()) {
      c = Serial.read();
      buf[i] = c;
      i++;
  }
  buf[i] = '\0';  // 文字列終わり
}

//-----------------------------------------------------------------------------------------------------
// Commandコントロール
void command()
{
  char c;
  int  i;
  
  // キー入力の確認,モータ回転
  if (Serial.available()){
    c = Serial.read();
    //Serial.flush();  // フラッシュじゃバッファクリアがうまく働かなかった
    while( Serial.available() && Serial.read()==c);        // 連続入力をキャンセル
    switch (c){    // 1文字でも文字列として読取るので,最初の1字を抜き出して分岐
       case 'w': if (form[mf][0]<90)  form[mf][0] +=5; dispState(); break; 
       case 'q': if (form[mf][0]>-90)    form[mf][0] -=5; dispState(); break; 
       case 's': if (form[mf][1]<90)  form[mf][1] +=5; dispState(); break; 
       case 'a': if (form[mf][1]>-90)    form[mf][1] -=5; dispState(); break; 
       case 'x': if (form[mf][2]<90)  form[mf][2] +=5; dispState(); break; 
       case 'z': if (form[mf][2]>-90)    form[mf][2] -=5; dispState(); break; 
       case 'r': if (form[mf][3]<90)  form[mf][3] +=5; dispState(); break; 
       case 'e': if (form[mf][3]>-90)    form[mf][3] -=5; dispState(); break; 
       case 'f': if (form[mf][4]<90)  form[mf][4] +=5; dispState(); break; 
       case 'd': if (form[mf][4]>-90)    form[mf][4] -=5; dispState(); break; 
       case 'v': if (form[mf][5]<90)  form[mf][5] +=5; dispState(); break; 
       case 'c': if (form[mf][5]>-90)    form[mf][5] -=5; dispState(); break; 
       case 'y': if (form[mf][6]<90)  form[mf][6] +=5; dispState(); break; 
       case 't': if (form[mf][6]>-90)    form[mf][6] -=5; dispState(); break; 
       case 'h': if (form[mf][7]<90)  form[mf][7] +=5; dispState(); break; 
       case 'g': if (form[mf][7]>-90)    form[mf][7] -=5; dispState(); break; 
       case 'n': if (form[mf][8]<90)  form[mf][8] +=5; dispState(); break; 
       case 'b': if (form[mf][8]>-90)    form[mf][8] -=5; dispState(); break; 
       case 'i': if (form[mf][9]<90)  form[mf][9] +=5; dispState(); break; 
       case 'u': if (form[mf][9]>-90)    form[mf][9] -=5; dispState(); break; 
       case 'k': if (form[mf][10]<90) form[mf][10]+=5; dispState(); break; 
       case 'j': if (form[mf][10]>-90)   form[mf][10]-=5; dispState(); break;     
       case ',': if (form[mf][11]<90) form[mf][11]+=5; dispState(); break; 
       case 'm': if (form[mf][11]>-90)   form[mf][11]-=5; dispState(); break;      
       case 'p': if (form[mf][12]<200) form[mf][12]+=5; dispState(); break; 
       case 'o': if (form[mf][12]>5)   form[mf][12]-=5; dispState(); break;  
       
       case '1': mfi=1; mf=mfi+mfb; dispState(); break; 
       case '2': mfi=2; mf=mfi+mfb; dispState(); break;
       case '3': mfi=3; mf=mfi+mfb; dispState(); break;
       case '4': mfi=4; mf=mfi+mfb; dispState(); break;
       case '5': mfi=5; mf=mfi+mfb; dispState(); break;
       case '6': mfi=6; mf=mfi+mfb; dispState(); break;
       case '7': mfi=7; mf=mfi+mfb; dispState(); break;
       case '8': mfi=8; mf=mfi+mfb; dispState(); break;
       case '9': mfi=9; mf=mfi+mfb; dispState(); break;
       case '0': mfi=0; mf=mfi+mfb; dispState(); break;
       case '-': if (mfb>0) mfb-=10; mf=mfi+mfb; dispState(); break; 
       case '^': if (mfb<20) mfb+=10; mf=mfi+mfb; dispState(); break; 

       case '!': mo=1; doMotion(mo); break; 
       case '"': mo=2; doMotion(mo); break; 
       case '#': mo=3; doMotion(mo); break; 
       case '$': mo=4; doMotion(mo); break;  
       case '%': mo=5; doMotion(mo); break;  
       case '&': mo=6; doMotion(mo); break;  
       case  39: mo=7; doMotion(mo); break;  // ' シフト7
       case '(': mo=8; doMotion(mo); break;  
       case ')': mo=9; doMotion(mo); break;  
       
       case 'P': dispOut(); break;                                                                       // ポーズとモーションデータを表示用出力    
       case 'L': Serial.println("upload form and motion"); loadAll(); Serial.println("done!"); break;  // ファイルから全データ書込み
       case 'S': saveAll(); break;                                                                          // ポーズとモーションの全データをファイルに書き出し     
       case 'W': formWrite(); Serial.println("Save form and motion to EEPROM."); break;            // ポーズをEEPROMに書込み
       case 'R': formRead();  Serial.println("Load form and motion from EEPROM."); break;            // ポーズをEEPROMに書込み
       case 'C': motionReset(); formReset(); Serial.println("Clear all form and motion."); break; // ポーズのクリア(配列で定義された初期値をセット)
       case 'N': if (mf<29){                                                                 // 現在のポーズを次のポーズにコピー 
                   for(i=0;i<13;i++) form[mf+1][i]=form[mf][i];
                   mf++;
                   dispState();
                 }
                 break; 
       case 'B': if (mf>0){                                                                  // 現在のポーズを前のポーズにコピー 
                   for( i=0;i<13;i++) form[mf-1][i]=form[mf][i];
                   mf--;
                   dispState();
                 }
                 break; 
       case 'A': for(i=0;i<10;i++) if (motion[mo][i]==99 && i<10) { motion[mo][i]=mf; break; }       // 現在のモーション番号に現在のポーズを追加                                                                     
                 doMotion(mo); 
                 break; 
       case 'D': for(i=0;i<10;i++) if (motion[mo][i]==99 && i>0) { motion[mo][i-1]=99; break; }      // 現在のモーション番号のポーズを1つ削除                                           
                 doMotion(mo); 
                 break;                
    }
  }   
}

//-----------------------------------------------------------------------------------------------------
// モーション実行
void doMotion(int n){
  Serial.print("Motion:"); Serial.println(n);
  for(int i=0; i<10; i++){
    if (motion[n][i]!=99){
      Serial.println(motion[n][i]);
      setForm(motion[n][i]);    // ポーズ変形,99の時はモーション終了
    }  
}
}

//-----------------------------------------------------------------------------------------------------
// ポーズ出力
void setForm(int n){
    leg11.write(90-form[n][0]+o[0]+r[0]); leg12.write(90+form[n][1]+o[1]+r[1]); leg13.write(90+form[n][2]+o[2]+r[2]);           
    leg21.write(90-form[n][3]+o[3]+r[3]); leg22.write(90-form[n][4]+o[4]+r[4]); leg23.write(90-form[n][5]+o[5]+r[5]);   
    leg31.write(90-form[n][6]+o[6]+r[6]); leg32.write(90-form[n][7]+o[7]+r[7]); leg33.write(90-form[n][8]+o[8]+r[8]);   
    leg41.write(90-form[n][9]+o[9]+r[9]); leg42.write(90+form[n][10]+o[10]+r[10]); leg43.write(90+form[n][11]+o[11]+r[11]);  
    delay(form[n][12]*10);
}

//-----------------------------------------------------------------------------------------------------
void setup() 
{ 
  Serial.begin(115200);          // 接続に使用
  leg11.attach(2);  leg12.attach(3);  leg13.attach(4);  
  leg21.attach(5);  leg22.attach(6);  leg23.attach(7);
  leg31.attach(8);  leg32.attach(9);  leg33.attach(10);
  leg41.attach(11); leg42.attach(12); leg43.attach(13);

  delay(1000);  
  formRead();                  // EEPROMからポーズデータの読出し
  setForm(0);
  // formReset();
  // formOut();
} 
 
//-----------------------------------------------------------------------------------------------------
void loop() 
{ 
  command();
  delay(15);
}

------------------------------------------

広告

〈 六足歩行ロボットキット 〉 KMR-M6 Ver.2 【近藤科学】

〈 四足歩行ロボットキット 〉 KMR-P4 Ver.1.5 【近藤科学】

< 前の記事へ


ページトップに戻る



ESP32 Wifi Bluetooth開発ボード

Arduino Nano Every
​​
Raspberry Pi pico

FPGA XILINX Artix-7