つづき
最後に映像を撮影して、YouTubeにアップしました。
[youtuasi] like a piglet move:「よつあし ポーク味」の動作確認
「ポーク味」用に作成したモーションを動かして撮影しました。
やはり「ポーク味」が動きが良くて扱いやすいように思います。さすがに地上を席捲した哺乳類タイプだけはあります。
おわりに
これで、「よつあし」で、当初予定していた3つのタイプの確認ができました。こうして色々作ってみると、四足歩行と言っても色々な足の運びが考えられて、奥が深いですね。また関節の向きをかえると、この三種類だけではなく、もっと多くのバリエーションが作れるので、自分だけのオリジナルな「風味」のロボットを作って遊んでみて下さい。もし作って動かせたら、Thingvers で Make の投稿をお願いします。だれかがMakeできたら、モデルをFIXしようと思います。
これからは暇を見つけては、ビルドマニュアルを作成したり、センサをつけたり、A/Iや画像処理を行ったりすると思いますが、でき次第このブログで発表して行きますので、たまに覗きに来て下さい。
また、構想中のidbox!のフルカラー化が完成したら、「よつあし」に
スキンを取り付けてよりリアルなロボットを作ろうと思っています。 (たぶん二年ぐらい先)
プログラムリスト
動画を撮影した時のスケッチをのせておきます。
これぐらい簡単だと、解説は必要ないですよね。
// Arduiroid Quadruped Robot 0.1 nakarobo 2018.11.18 // Model https://www.thingiverse.com/thing:3018095 // HP https://www.nakarobo.com/youtuasi // File youtuasiPorkTest.ino // Servo #include <Servo.h> #define MAX_SERVO_NUM 8 Servo servo[MAX_SERVO_NUM+1]; //Arduroid4 (Top View) //FLONT // ----- ----- // | 2 | | 6 | // | P05 | | P03 | // ----- ----- ----- ----- // | 1 | | 5 | // | P04 | | P02 | // ----- ----- // | 3 | | 7 | // | P08 | | P06 | // ----- ----- ----- ----- // | 4 | | 7 | // | P09 | | P09 | // ----- ----- //BACK // Setup First Power On at Once void setup() { // put your setup code here, to run once: Serial.begin(9600); while (!Serial); // Servo Test attachServo(); detachServo(); } // MainLoop void loop() { // if there's any serial available, read it: while (Serial.available() > 0) { // servo ON attachServo(); char command = Serial.read(); switch (command){ case '0': // 基本姿勢 Basic Position set8Pos(90,90,90,90,90,90,90,90); delay(300); break; case '1': // 伸び Stretch set8Pos(150,10,40,170,40,170,150,10); delay(300); break; case '2': // 前進 Forward set8Pos(120, 60, 50, 50, 60, 60,130, 90); delay(500); set8Pos(120,110, 50, 90, 60,110,130,130); delay(500); break; case '3': // お辞儀 Bowing set8Pos(150,10,40,70,40,180,150,110); delay(300); break; case '4': // 左旋回 Left Turn set8Pos(120,110,50,70,60,70,130,110); delay(300); set8Pos( 90,110,30,90,30,90,90,110); delay(100); set8Pos( 90,110,170,90,170,90,90,110); delay(300); set8Pos( 120,90,50,60,60,70,130,90); delay(250); set8Pos(120,110,50,70,60,70,130,110); delay(300); break; case '5': // 立つ Normal Position set8Pos(120,110,50,70,60,70,130,110); delay(300); break; case '6': // 右旋回 Right Turn set8Pos(120,110,50,70,60,70,130,110); delay(300); set8Pos( 150,90,90,70,90,70,150,90); delay(100); set8Pos( 10,90,90,60,90,60,10,90); delay(250); set8Pos(120,110,50,70,60,70,130,110); delay(300); break; case '7': // お座り Sit Down set8Pos(90,110,30,20,90,70,150,160); delay(300); break; case '8': // 後進 Back set8Pos(120, 90,70,120,60, 60,110,90); delay(500); set8Pos(120,120,70, 90,60, 90,110,60); delay(500); break; case 'l': // たつ Stand Up set8Pos( 90, 90, 70, 20, 90, 90,110,160); delay(250); set8Pos( 90,160, 90, 60, 90, 20, 90, 130); delay(500); set8Pos( 90,160, 70, 60, 90, 20, 120, 120); delay(250); break; case '9': // 伏せ lay set8Pos(150,180,30,0,30,0,150,180); delay(300); break; case 'D': // 待つ Wait case 'd': delay(300); break; case 'R': // 走る Run case 'r': set8Pos(120, 60, 70, 50, 60, 60,110, 90); delay(125); set8Pos(120,110, 70, 90, 60,110,110,120); delay(125); set8Pos(120, 60, 70, 50, 60, 60,110, 90); delay(125); set8Pos(120,110, 70, 90, 60,110,110,120); delay(125); set8Pos(120, 60, 70, 50, 60, 60,110, 90); delay(125); set8Pos(120,110, 70, 90, 60,110,110,120); delay(125); break; case 'B': // 後ろに走る Back Fast case 'b': set8Pos(120, 70,70,120,60, 60,110,90); delay(125); set8Pos(120,120,70, 90,60,110,110,60); delay(125); set8Pos(120, 70,70,120,60, 60,110,90); delay(125); set8Pos(120,120,70, 90,60,110,110,60); delay(125); set8Pos(120, 70,70,120,60, 60,110,90); delay(125); set8Pos(120,120,70, 90,60,110,110,60); delay(125); break; } // switch // SERVO Set command if ( command == 'S' || command == 's' ) // 'S' is Servo Command "S,Servo_no,Angle" { Serial.print(command); Serial.print(','); int servoNo = Serial.parseInt(); Serial.print(servoNo); Serial.print(','); int servoAngle = Serial.parseInt(); Serial.print(servoAngle); Serial.println(); if ( 0 <= servoNo && servoNo < MAX_SERVO_NUM+1 ) { // Single Servo Move servo[servoNo].write(servoAngle); // Wait Servo Move delay(300); // 180/60(°/100msec)=300(msec) } } // SERVO Set END // SERVO All command if ( command == 'A' || command == 'a' ) // 'A' is Servo All Command "A,Angle0, Angle1...Angle7" { Serial.print(command); // read Angle from Serial int angle[MAX_SERVO_NUM]; for (int i = 0; i < MAX_SERVO_NUM; i++) { angle[i] = Serial.parseInt(); Serial.print(','); Serial.print(angle[i]); } Serial.println(); // servo Move set8Pos( angle[0], angle[1], angle[2], angle[3], angle[4], angle[5], angle[6], angle[7] ); // Wait Servo Move delay(300); } // SERVO All End // Servo OFF detachServo(); } // End while }// End loop // attach ServoMotors void attachServo() { // attach Pin to ServoMotor servo[1].attach(4); servo[2].attach(5); servo[3].attach(8); servo[4].attach(9); servo[5].attach(2); servo[6].attach(3); servo[7].attach(6); servo[8].attach(7); } // dettach ServoMotors void detachServo() { servo[1].detach(); servo[2].detach(); servo[3].detach(); servo[4].detach(); servo[5].detach(); servo[6].detach(); servo[7].detach(); servo[8].detach(); } // Set 8 ServoMotor angles void set8Pos(int a, int b, int c, int d, int e, int f, int g, int h){ servo[1].write(a); servo[2].write(b); servo[3].write(c); servo[4].write(d); servo[5].write(e); servo[6].write(f); servo[7].write(g); servo[8].write(h); } // End //---------------------
おしまい