Fusion360でガンダムフレームを作った
何年も前ですが、MGガンダムバルバトスを参考に、3DCADソフトFusion360でガンダムフレームを作りました。
PCのフォルダを整理していたら見つけたので、記事にしてみました。
▼インストの図面から、ある程度の形を出します。
▼頭の造形。複雑すぎてかなり時間がかかりました。
▼上半身。胴体はシリンダが多いです。
▼脚部。裏側がスカスカの脛ですが、このカバーっぽいデザイン好きです。
▼レンダリングおためし
▼後に3Dプリンター出力も考え、パーツ分割しています。
▼シリンダーも、疑似ボールジョイント的なものを作りました。
▼色付&レンダリング
▼プリンター出力。FDMなので大分荒いです。
実はすごくデカイ(1/30くらい?)
▼ガンプラとツーショット
現時点では頭と胴しか作れてませんが、いつか全身作りたいですね。
ご精読ありがとうございました。
【オリロボ】人型重機「WoodsWalker」レビュー
今回は、械電八屋オリジナルデザインロボット
自律人型土木作業用重機「WoodsWalker」
をFusion360で製作しました。
コンセプトは重機風の人型ロボットです。
▼正面
各関節はモータorシリンダ駆動。
▼背面
▼カメラヘッド
▼胸部
制御基板系をカバー内に収納(という設定)
▼背面エネルギーパック:燃料系の収納
▼エンジンパック:動力源内蔵
▼腰駆動軸・ターレット
戦車や重機のターレット風に
▼上腕
▼肩部:ヨー軸は油圧シリンダ駆動
▼前腕・バケット
大木の掴み・クラッシャー的な用途
▼下腿・足①
膝関節は大きく曲げた状態。重心を安定させる姿勢にしています。
▼下腿・足②
足と地面の角度はシリンダ調節
▼足裏
滑り止め用のスリット
おまけ
▼色なし
▼スケッチデザイン
大分変更しました。
▼3Dプリンタで作ってみました。この後成形・塗装を行う予定です。
ご覧いただきありがとうございました。
【人型ロボ開発記#2】2足歩行モーション(3軸脚)
脚の動作過程・逆運動学は同じものです。(#1参照)
klaft0729.hatenablog.jp
Arduinoコードは2脚を別々で動作させるため、時間変数で座標位置を算出するコードに改良しています。
各脚のモーションは反転しているものとし、右脚が踏み込む際に、左脚が地面を蹴る動作となっています。
↓実行結果はこちらです。
www.youtube.com
↓Arduinoコード
#include <Servo.h> int Servo1_Socket = 3; int Servo2_Socket = 5; int Servo3_Socket = 6; int Servo4_Socket =9; int Servo5_Socket =10; int Servo6_Socket =11; Servo servo1; Servo servo2; Servo servo3; Servo servo4; Servo servo5; Servo servo6; float th1 = 0, th2 = 0, th3 = 0, th4 = 0, th5 = 0, th6 = 0; float phi = 3.14; float L1 = 60.2, L2 = 60.2, L3 = 33; float xR, yR, alphaR, xL, yL, alphaL; float t, totalTime, lamda; float xR_p1, yR_p1, xR_p2, yR_p2; float alphaR_p1, alphaR_p2; float xL_p1, yL_p1, xL_p2, yL_p2; float alphaL_p1, alphaL_p2; void setup(){ Serial.begin(115200); servo1.attach(Servo1_Socket,500,2500); servo2.attach(Servo2_Socket,500,2500); servo3.attach(Servo3_Socket,500,2500); servo4.attach(Servo4_Socket,500,2500); servo5.attach(Servo5_Socket,500,2500); servo6.attach(Servo6_Socket,500,2500); set_servo(); //初期座標 xR = 0; yR = 116.56; alphaR = 0; xL = 0; yL = 116.56; alphaL = 0; Serial.println("Initialize"); } void loop(){ //process1 R:1-2 L:5-1(1) Serial.println("process1/////////////////////////////////////////////////"); //入力座標 xR_p1 = 70; yR_p1 = 90; alphaR_p1 = 60; xR_p2 = 53; yR_p2 = 103; alphaR_p2 = 60; xL_p1 = -70; yL_p1 = 90; alphaL_p1 = 120; xL_p2 = -35; yL_p2 = 90; alphaL_p2 = 105; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process2 R:2-3 L:5-1(2) Serial.println("process2/////////////////////////////////////////////////"); //入力座標 xR_p1 = 53; yR_p1 = 103; alphaR_p1 = 60; xR_p2 = 0; yR_p2 = 110; alphaR_p2 = 90; xL_p1 = -35; yL_p1 = 90; alphaL_p1 = 105; xL_p2 = -17.5; yL_p2 = 90; alphaL_p2 = 82.5; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process3 R:3-4 L:5-1(3) Serial.println("process3/////////////////////////////////////////////////"); //入力座標 xR_p1 = 0; yR_p1 = 110; alphaR_p1 = 90; xR_p2 = -62; yR_p2 = 98; alphaR_p2 = 120; xL_p1 = -17.5; yL_p1 = 90; alphaL_p1 = 82.5; xL_p2 = 56.88; yL_p2 = 90; alphaL_p2 = 65.62; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process4 R:4-5 L:5-1(4) Serial.println("process4/////////////////////////////////////////////////"); //入力座標 xR_p1 = -62; yR_p1 = 98; alphaR_p1 = 120; xR_p2 = -70; yR_p2 = 90; alphaR_p2 = 120; xL_p1 = 56.88; yL_p1 = 90; alphaL_p1 = 65.62; xL_p2 = 70; yL_p2 = 90; alphaL_p2 = 60; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process5 R:5-1(1) L:1-2 Serial.println("process5/////////////////////////////////////////////////"); //入力座標 xR_p1 = -70; yR_p1 = 90; alphaR_p1 = 120; xR_p2 = -35; yR_p2 = 90; alphaR_p2 = 105; xL_p1 = 70; yL_p1 = 90; alphaL_p1 = 60; xL_p2 = 53; yL_p2 = 103; alphaL_p2 = 60; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process6 R:5-1(2) L:2-3 Serial.println("process6/////////////////////////////////////////////////"); //入力座標 xR_p1 = -35; yR_p1 = 90; alphaR_p1 = 105; xR_p2 = -17.5; yR_p2 = 90; alphaR_p2 = 82.5; xL_p1 = 53; yL_p1 = 103; alphaL_p1 = 60; xL_p2 = 0; yL_p2 = 110; alphaL_p2 = 90; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process7 R:5-1(3) L:3-4 Serial.println("process7/////////////////////////////////////////////////"); //入力座標 xR_p1 = -17.5; yR_p1 = 90; alphaR_p1 = 82.5; xR_p2 = 56.88; yR_p2 = 90; alphaR_p2 = 65.62; xL_p1 = 0; yL_p1 = 110; alphaL_p1 = 90; xL_p2 = -62; yL_p2 = 98; alphaL_p2 = 120; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } //process8 R:5-1(4) L:4-5 Serial.println("process8/////////////////////////////////////////////////"); //入力座標 xR_p1 = 56.88; yR_p1 = 90; alphaR_p1 = 65.62; xR_p2 = 70; yR_p2 = 90; alphaR_p2 = 60; xL_p1 = -62; yL_p1 = 98; alphaL_p1 = 120; xL_p2 = -70; yL_p2 = 90; alphaL_p2 = 120; t = 0; totalTime = 1; while(t <= 0.9){ Coordinate(); ik(); set_servo(); thprint(); t = t + 0.1; } } void Coordinate(){ lamda = t / totalTime; //座標計算 //Right Leg xR_p1 = xR_p1 + (xR_p2 - xR_p1) * lamda; yR_p1 = yR_p1 + (yR_p2 - yR_p1) * lamda; alphaR_p1 = alphaR_p1 + (alphaR_p2 - alphaR_p1) * lamda; xR = xR_p1; yR = yR_p1; alphaR = alphaR_p1; //Left Leg xL_p1 = xL_p1 + (xL_p2 - xL_p1) * lamda; yL_p1 = yL_p1 + (yL_p2 - yL_p1) * lamda; alphaL_p1 = alphaL_p1 + (alphaL_p2 - alphaL_p1) * lamda; xL = xL_p1; yL = yL_p1; alphaL = alphaL_p1; } void ik(){ //逆運動学計算 float xR1, yR1, kR, th1_r, th2_r, th3_r, alphaR_r; float xL1, yL1, kL, th4_r, th5_r, th6_r, alphaL_r; float AR, BR, CR, DR; float AL, BL, CL, DL; //Right ik alphaR_r = alphaR * phi / 180; xR1 = xR - L3 * cos(alphaR_r); yR1 = yR - L3 * sin(alphaR_r); AR = xR1*xR1 + yR1*yR1 + L1*L1 + L2*L2; BR = xR1*xR1 + yR1*yR1; CR = L1*L1*L1*L1 + L2*L2*L2*L2; kR = sqrt(AR * AR - 2 * (BR * BR + CR)); th1_r = atan2(yR1, xR1) - atan2(kR, BR + L1*L1 - L2*L2); th2_r = atan2(kR, BR - L1*L1 - L2*L2); th3_r = phi / 2 + alphaR_r - (th1_r + th2_r); th1 = th1_r * 180 / phi; th2 = th2_r * 180 / phi; th3 = th3_r * 180 / phi; //Left ik alphaL_r = alphaL * phi / 180; xL1 = xL - L3 * cos(alphaL_r); yL1 = yL - L3 * sin(alphaL_r); AL = xL1 * xL1 + yL1 * yL1 + L1*L1 + L2*L2; BL = xL1 * xL1 + yL1 * yL1; CL = L1*L1*L1*L1 + L2*L2*L2*L2; kL = sqrt(AL * AL - 2 * (BL * BL + CL)); th4_r = atan2(yL1, xL1) - atan2(kL, BL + L1*L1 - L2*L2); th5_r = atan2(kL, BL - L1*L1 - L2*L2); th6_r = phi / 2 + alphaL_r - (th4_r + th5_r); th4 = th4_r * 180 / phi; th5 = th5_r * 180 / phi; th6 = th6_r * 180 / phi; } void set_servo(){ //サーボ出力 servo1.write(th1); servo2.write(th2); servo3.write(th3); servo4.write(th4); servo5.write(th5); servo6.write(th6); delay(5); } void thprint(){ //座標・サーボ角モニタ Serial.print("xR:"); Serial.print(xR); Serial.print(" yR:"); Serial.print(yR); Serial.print(" alphaR:"); Serial.print(alphaR); Serial.print(" th1:"); Serial.print(th1); Serial.print(" th2:"); Serial.print(th2); Serial.print(" th3:"); Serial.println(th3); Serial.print("xL:"); Serial.print(xL); Serial.print(" yL:"); Serial.print(yL); Serial.print(" alphaL:"); Serial.print(alphaR); Serial.print(" th4:"); Serial.print(th4); Serial.print(" th5:"); Serial.print(th5); Serial.print(" th6:"); Serial.println(th6); }
シリアルモニタで各足先座標・関節角をモニタ出来ます。
ご覧いただきありがとうございました。
【人型ロボ開発記#1】3軸脚歩行モーション
「ゲームのモーションをリアルロボットで再現したい」
TPV系のゲームをプレイしているとき、ふと思いつきました。
ダッシュ・ジャンプ・クライミング・剣技・射撃...
機械が動くシーンを見るのが好きな私ですが、ロボットにダイナミックなアクションを実行させる面白さを追求してみたいと思いました。
現実世界でロボットを動かすことは、地形や障害物との衝突、機体重心制御、機体の反応速度などといった観点から、ゲーム世界でキャラクターを操作するより難しく、歩行という単純動作においても複雑な制御を必要とします。
市販の人型ロボやロボットアーム等をほぼ触ったことが無い私は、まず、人型ロボットをサーボ使って自作するところから、始めようと思います。
1.人型モデルを考える
人の骨格・筋肉構造から、ロボットモデルを決定します。
モーションを実行するために、まず最低限の構成で組んでみます。
部位は胴体・腰・腕2部・脚2部。軸位置は腰2軸・肩3軸・肘1軸・手首2軸・股3軸・膝1軸・足首3軸(片側)とします。(図1)
サーボの電力消費、多軸型モーションの複雑さ、本体重量等の制限を考慮し、1号機の制作を目指します。
2.「3軸脚」
今回は、下半身の歩行モーションを作ってみました。実際に歩行させるのは大分先になりますが、ロボットを宙に浮かせた状態でモーションを実行させます。
下半身のモデルは目標が片側計5軸ですが、まずは簡単なモーションを見るため、3軸構成の脚モデル「3軸脚」を組みます。(図2)
サーボはLewansoulのLDX-218を使用。ブラケットと3Dプリントパーツでモデルを組み、塩ビパイプで支柱を作成しました。制御基板はArduinoを使います。
↓回路図
3.歩行モーション1「5ステップ型」
歩行モーションの制作にあたり、まず足先の軌道を設定します。仮想地面を足裏がなでるようなモーションを目標にします。歩行動作の順番は
①前脚位置 ②踏み込み ③地面をなでる ④蹴り ⑤後ろ脚位置
とし、このループを繰り返します。
この5段階の足位置座標を目標とし、サーボを動作させることにより、歩行モーションを再現します。5個の足先座標を点々と移動する動作であるため、カクカクな歩行になります。実行結果はこちらです。
↓Arduinoコード
#include <Servo.h> int Servo1_Socket = 3; int Servo2_Socket = 5; int Servo3_Socket = 6; Servo servo1; Servo servo2; Servo servo3; float th1 = 0, th2 = 0, th3 = 0; float phi; float L1 = 60.2, L2 = 60.2, L3 = 33; float x,y,alpha; void setup(){ servo1.attach(Servo1_Socket,500,2500); servo2.attach(Servo2_Socket,500,2500); servo3.attach(Servo3_Socket,500,2500); set_servo(); x = 0; y = 116.56; alpha = 0; } void loop(){ //process1 x = 50.90; y = 105.14; alpha = 60; ik(); set_servo(); //process2 x = 20; y = 112.23; alpha = 60; ik(); set_servo(); //process3 x = 0; y = 116.56; alpha = 90; ik(); set_servo(); //process4 x = -20; y = 112.23; alpha = 120; ik(); set_servo(); //process5 x = -50.90; y = 105.14; alpha = 120; ik(); set_servo(); } void ik(){ float x1, y1, phi, ld, k, th_r1, th_r2, th_r3, alpha_r; float A, B, C, D; alpha_r = alpha * 3.14/180; x1 = x - L3 * cos(alpha_r); y1 = y - L3 * sin(alpha_r); A = x1*x1 + y1*y1 + L1*L1 + L2*L2; B = x1*x1 + y1*y1; C = L1*L1*L1*L1 + L2*L2*L2*L2; k = sqrt(A*A - 2 * (B*B + C)); th_r1 = atan2(y1, x1) - atan2(k, B + L1*L1 - L2*L2); th_r2 = atan2(k, B - L1*L1 - L2*L2); th_r3 = 3.14/2 + alpha_r - (th_r1 + th_r2); th1 = th_r1 * 180/3.14; th2 = th_r2 * 180/3.14; th3 = th_r3 * 180/3.14; } void set_servo(){ servo1.write(th1); servo2.write(th2); servo3.write(th3); }
4.歩行モーション2「スイープ型」
次は5ステップ型を改良し、スムーズなモーションを目指します。各座標間の移動を直線補間で関数的に表し、一定時間ごとの座標を逐次計算するコードを作りました。なお、足裏で地面をなでる動作は、足首軸の回転に伴い座標移動を行うものとしています。実行結果はこちらです。
↓Arduinoコード
#include <Servo.h> int Servo1_Socket = 3; int Servo2_Socket = 5; int Servo3_Socket = 6; Servo servo1; Servo servo2; Servo servo3; float th1 = 0, th2 = 0, th3 = 0; float phi = 3.14; float L1 = 60.2, L2 = 60.2, L3 = 33; float x,y,alpha,xH,yH,xT,yT; float q = 55, p = 30, r = 65, t = 60, n = 140; void setup(){ servo1.attach(Servo1_Socket,500,2500); servo2.attach(Servo2_Socket,500,2500); servo3.attach(Servo3_Socket,500,2500); set_servo(); x = 70; y = 90; alpha = 60; } void loop(){ //process1-2 while(x >= 53){ y = -0.7349 * x + 141.44; ik(); set_servo(); x = x - 1; //process2-3 xH = 40; yH = 110; alpha = 60; while(alpha <= 90){ x = xH + 15 * cos(phi/2 - alpha * phi/180); y = yH - 15 * sin(phi/2 - alpha * phi/180); ik(); set_servo(); alpha++; xH = xH -q/p; } //process3-4 xT = 25; yT = yH; while(xT >= 0){ x = -( 25 * cos(alpha * phi/180 - phi/2) - xT ); y = yT - 25 * sin(alpha * phi/180 - phi/2); ik(); set_servo(); alpha ++; xT = xT - r/p; } while(xT <= 40){ x = -( xT + 25 * cos(alpha * phi/180 - phi/2)); y = yT - 25 * sin(alpha * phi/180 - phi/2); ik(); set_servo(); alpha ++; xT = xT + r/p; } //process4-5 x = -62; while(x >= -70){ y = 0.8383 * x + 148.68; ik(); set_servo(); thprint(); x = x -1; } //process5-1 while(x <= 70){ y = 90; ik(); set_servo(); thprint_2(); x++; alpha = alpha - t/n; } } void ik(){ float x1, y1, phi, ld, k, th_r1, th_r2, th_r3, alpha_r; float A, B, C, D; alpha_r = alpha * 3.14/180; x1 = x - L3 * cos(alpha_r); y1 = y - L3 * sin(alpha_r); A = x1*x1 + y1*y1 + L1*L1 + L2*L2; B = x1*x1 + y1*y1; C = L1*L1*L1*L1 + L2*L2*L2*L2; k = sqrt(A*A - 2 * (B*B + C)); th_r1 = atan2(y1, x1) - atan2(k, B + L1*L1 - L2*L2); th_r2 = atan2(k, B - L1*L1 - L2*L2); th_r3 = 3.14/2 + alpha_r - (th_r1 + th_r2); th1 = th_r1 * 180/3.14; th2 = th_r2 * 180/3.14; th3 = th_r3 * 180/3.14; } void set_servo(){ servo1.write(th1); servo2.write(th2); servo3.write(th3); }
次回は軸数7の制御方法を考え、2脚での歩行モーションを再現しようと思います。
ご覧いただきありがとうございました。