此时3/4的暑假已经过去......本以为可以歇一会了,马上工作站通知要中期答辩了,我就赶紧上手看看怎么做步态,发现是真不会,这条狗这怎么让它动起来啊啊啊啊啊啊啊啊啊!!!!!!去问老师,老师的回答非常浅显易懂:你上网焯一下,反正你一个高中牲没必要全部原创。
#include <Servo.h>
Servo s[12];
int zeroPositions[12] = {90, 95, 90, 90, 80, 90, 90, 95, 90, 90, 80, 90};
int directions[12] = {-1, -1, -1, -1, +1, +1, +1, -1, -1, +1, +1, +1};
const float l = 5.8;
const float L = 6.0;
void pos(float x, float y, float z, int leg){
float groinRadians = atan(y/z);
float groinDegrees = groinRadians * (180/PI);
float hipRadians1 = atan(x/z);
float z1 = sqrt(sq(z) + sq(y) + sq(x));
float hipRadians2 = acos(z1/(2*l));
float hipDegrees = (hipRadians1 + hipRadians2) * (180/PI);
float kneeRadians = PI - 2*hipRadians2;
float kneeDegrees = 180 - kneeRadians * (180/PI);
s[3*leg].write(zeroPositions[3*leg] + directions[3*leg]*groinDegrees);
s[3*leg+1].write(zeroPositions[3*leg+1] + directions[3*leg+1]*hipDegrees);
s[3*leg+2].write(zeroPositions[3*leg+2] + directions[3*leg+2]*kneeDegrees);
}
void translate(float x, float y, float z){
for (int leg = 0; leg<=3; leg++){
pos(x,y,z,leg);
}
}
void rotate(float theta){
float thetaRadians = theta * (PI/180);
float d = tan(thetaRadians) * (L/2);
Serial.println(d);
pos(0,0,8.0+d,0);
pos(0,0,8.0+d,1);
pos(0,0,8.0-d,2);
pos(0,0,8.0-d,3);
}
void takeStep(float stepSpeed, float stepLength){
pos(+stepLength,0,9,0);
pos(-stepLength,0,9,1);
pos(-stepLength,0,9,2);
pos(+stepLength,0,9,3);
delay(stepSpeed);
pos(+stepLength,0,8,0);
pos(-stepLength,0,9,1);
pos(-stepLength,0,9,2);
pos(+stepLength,0,8,3);
delay(stepSpeed);
pos(-stepLength,0,8,0);
pos(+stepLength,0,9,1);
pos(+stepLength,0,9,2);
pos(-stepLength,0,8,3);
delay(stepSpeed);
pos(-stepLength,0,9,0);
pos(+stepLength,0,9,1);
pos(+stepLength,0,9,2);
pos(-stepLength,0,9,3);
delay(stepSpeed);
pos(-stepLength,0,9,0);
pos(+stepLength,0,8,1);
pos(+stepLength,0,8,2);
pos(-stepLength,0,9,3);
delay(stepSpeed);
pos(+stepLength,0,9,0);
pos(-stepLength,0,8,1);
pos(-stepLength,0,8,2);
pos(+stepLength,0,9,3);
delay(stepSpeed);
}
void sideStep(){
pos(0,0,8,0);
pos(0,0,8,1);
pos(0,0,8,2);
pos(0,0,8,3);
delay(100);
pos(0,0,10,0);
pos(0,2,8,1);
pos(0,0,10,2);
pos(0,2,8,3);
delay(100);
pos(0,3,9,0);
pos(0,-3,9,1);
pos(0,3,9,2);
pos(0,-3,9,3);
delay(500);
pos(0,0,9,0);
pos(0,-3,9,1);
pos(0,0,9,2);
pos(0,-3,9,3);
delay(100);
pos(0,0,9,0);
pos(0,0,9,1);
pos(0,0,9,2);
pos(0,0,9,3);
delay(100);
}
void setup() {
// put your setup code here, to run once:
delay(1000);
Serial.begin(9600);
for(int i=0; i<12; i++){
s[i].attach(i + 2);
}
for(int i=0; i<12; i++){
s[i].write(zeroPositions[i]);
}
delay(300);
Serial.print("Ready.");
}
void loop() {
// put your main code here, to run repeatedly:
}