多サーボモータを使う(6脚歩行ロボットの場合)
サーボモータを沢山使う多関節ロボットの作り方の参考になればと思い6脚歩行ロボットを制作しました。

上から見たところ(このポーズをサーボ角度0度の基本姿勢としてくみ上げました。)

各関節2個使用し6脚でサーボ12個にてくみ上げました。
関節を沢山動かすプログラムのコツは、ポーズをいくつか制作しその間の動きを「補完する」ことにあります。プログラム中ではその補完をp2Pose()という関数で行っています。
此の場合は7種類のポーズを制作し、その間の繋ぎ方で前後左右旋回を実現しています。
p2Pose(分割数、サンプリングタイム、ポーズ1、ポーズ2)
分割数:補完の荒さ、小さいと動きが荒くなります。大きすぎるとその分、動きが遅くなります。
サンプリングタイム:指令値を出す間隔、荒いとぎこちなくなります。※20msec以下にしてもあまり意味はありません。
ポーズ1:現在の姿勢
ポーズ2:次の姿勢
トライポッド歩行のプログラムとその様子です。
サンプルプログラム(ポーズのデータが入っているのでちょっと長いです。)
必ずベースには14サーボ制御の14サーボ基本サンプルプログラムを使用してください。
#include "DSP28x_Project.h" // Device Headerfile and Examples Include File
#include "NolibM.h"
/* ニュートラル状態設定 */
#define neuServoPos1 60.0 // 右前先
#define neuServoPos2 0 // 右前胴
#define neuServoPos3 60.0 // 右中先
#define neuServoPos4 0 // 右中胴
#define neuServoPos5 60.0 // 右後先
#define neuServoPos6 0 // 右後胴
#define neuServoPos8 -60.0 // 左前先
#define neuServoPos9 0 // 左前胴
#define neuServoPos10 -60.0 // 左中先
#define neuServoPos11 0 // 左中胴
#define neuServoPos12 -60.0 // 左後先
#define neuServoPos13 0 // 左後胴
/* モーションパラメータ */
#define LEGUP 45.0 //脚の上下幅 deg
#define LEGFB 25.0 //脚の前後幅 deg
static int svid[]={1,2,3,4,5,6,8,9,10,11,12,13}; //使用サーボのIDを定義
/* ポスチャーデータ列 */
static float motion[][12]={
{// posture ID0 Neutral
neuServoPos1,
neuServoPos2,
neuServoPos3,
neuServoPos4,
neuServoPos5,
neuServoPos6,
neuServoPos8,
neuServoPos9,
neuServoPos10,
neuServoPos11,
neuServoPos12,
neuServoPos13
},//posture ID1 WALKING1
{
neuServoPos1,
neuServoPos2 +LEGFB,
neuServoPos3,
neuServoPos4 -LEGFB,
neuServoPos5,
neuServoPos6 +LEGFB,
neuServoPos8,
neuServoPos9 +LEGFB,
neuServoPos10,
neuServoPos11 -LEGFB,
neuServoPos12,
neuServoPos13 +LEGFB
}
,//posture ID2 WALKING2
{
neuServoPos1,
neuServoPos2 -LEGFB,
neuServoPos3,
neuServoPos4 +LEGFB,
neuServoPos5,
neuServoPos6 -LEGFB,
neuServoPos8,
neuServoPos9 -LEGFB,
neuServoPos10,
neuServoPos11 +LEGFB,
neuServoPos12,
neuServoPos13 -LEGFB
}
,// posture ID3 WALKING-TRANSITION 1
{
neuServoPos1,
neuServoPos2,
neuServoPos3 -LEGUP,
neuServoPos4,
neuServoPos5,
neuServoPos6,
neuServoPos8 +LEGUP,
neuServoPos9,
neuServoPos10,
neuServoPos11,
neuServoPos12 +LEGUP,
neuServoPos13
},// posture ID4 WALKING-TRANSITION 1
{
neuServoPos1 - LEGUP,
neuServoPos2,
neuServoPos3,
neuServoPos4,
neuServoPos5 - LEGUP,
neuServoPos6,
neuServoPos8,
neuServoPos9,
neuServoPos10 + LEGUP,
neuServoPos11,
neuServoPos12,
neuServoPos13
}
,//posture ID5 TURN 1
{
neuServoPos1,
neuServoPos2 -LEGFB,
neuServoPos3,
neuServoPos4 +LEGFB,
neuServoPos5,
neuServoPos6 -LEGFB,
neuServoPos8,
neuServoPos9 +LEGFB,
neuServoPos10,
neuServoPos11 -LEGFB,
neuServoPos12,
neuServoPos13 +LEGFB
}
,//posture ID6 TURN 2
{
neuServoPos1,
neuServoPos2 +LEGFB,
neuServoPos3,
neuServoPos4 -LEGFB,
neuServoPos5,
neuServoPos6 +LEGFB,
neuServoPos8,
neuServoPos9 -LEGFB,
neuServoPos10,
neuServoPos11 +LEGFB,
neuServoPos12,
neuServoPos13 -LEGFB
}
};
// These are defined by the linker (see F2808.cmd)
extern Uint16 RamfuncsLoadStart;
extern Uint16 RamfuncsLoadEnd;
extern Uint16 RamfuncsRunStart;
volatile struct EPWM_REGS *ePWM[] =
{ &EPwm1Regs, //intentional: (ePWM[0] not used)
&EPwm1Regs,
&EPwm2Regs,
&EPwm3Regs,
&EPwm4Regs,
&EPwm5Regs,
&EPwm6Regs,
&EPwm7Regs,
};
/**********************************/
/****** setPose **********/
/**********************************/
int setPose(int pose_id)
{
int ii;
for(ii=0;ii<12;ii++)
{
servo(motion[pose_id][ii],svid[ii]);
}
return 0;
}
/**********************************/
/**** p2Pose *******/
/**********************************/
void p2Pose(int div,int sampleT, int pose1, int pose2)
{
int diff[12],i,j;
for(i=0;i<12;i++)
{
diff[i]=(motion[pose2][i]-motion[pose1][i]);
diff[i]=diff[i]/div;
servo(motion[pose1][i],svid[i]);
}
for(j=1;j<=div;j++)
{
for(i=0;i<12;i++)
{
servo(motion[pose1][i]+j*diff[i],svid[i]);
}
wait(sampleT);
}
}
}
void main(void)
{
int ii;
initNolibM(); //初期化
//Set Neutral Position
for(ii=0;ii<12;ii++)
{
servo(motion[0][ii],svid[ii]);
GpioDataRegs.GPBTOGGLE.bit.GPIO39=1;
}
while(1)
{
while(sw1(OFF)); //スイッチが入るまで待つ
for(ii=0;ii<6;ii++)//動き出しまで3秒待つ
{
GpioDataRegs.GPBTOGGLE.bit.GPIO39=1; //CPUのLEDが点滅
wait(500);
}
p2Pose(20,20,0,3);
//start acceleration
for(ii=20;ii>4;ii-=10)
{
p2Pose(ii,20,3,1);
p2Pose(ii,20,1,4);
p2Pose(ii,20,4,2);
p2Pose(ii,20,2,3);
}
//high speed walking
for(ii=0;ii<8;ii++)
{
p2Pose(5,20,3,1);
p2Pose(5,20,1,4);
p2Pose(5,20,4,2);
p2Pose(5,20,2,3);
}
for(ii=5;ii<21;ii+=10)
{
p2Pose(ii,20,3,1);
p2Pose(ii,20,1,4);
p2Pose(ii,20,4,2);
p2Pose(ii,20,2,3);
}
// turn left
for(ii=0;ii<3;ii++)
{
p2Pose(15,20,3,5);
p2Pose(15,20,5,4);
p2Pose(15,20,4,6);
p2Pose(15,20,6,3);
}
p2Pose(20,20,3,0);
} //while end
}
ちなみにロボットの足のサーボモータはKONDO KRS788HVを使用しています。
また足の棒はIKEAにてうっています「鍋ぶたオーガナイザー」
コレ

ステンレスでとても奇麗だったので脚にしました。しかも安いんですよ(499円)ステンレス加工するとかなり高価になるので迷わずゲットしました。14本入っているので二体は作れますね。



