範例:OTTO忍者變身
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 | #include <Servo.h>
const uint8_t ServoLeftLegPin =15; // D8 or 15
const uint8_t ServoRightLegPin=2; // D4 or 2
const uint8_t ServoLeftFootPin =13; // D7 or 13
const uint8_t ServoRightFootPin =0; // D3 or 0
const uint8_t ServoLeftArmPin =D0; // D0 or 16
const uint8_t ServoRightArmPin =3; // RX or 3
const uint8_t ServoHeadPin =1; // TX or 1
Servo myservoLeftLeg;
Servo myservoLeftFoot;
Servo myservoRightFoot;
Servo myservoRightLeg;
Servo myservoLeftArm;
Servo myservoRightArm;
Servo myservoHead;
int LA0= 60 +0; // Left Leg standing Position; 0 = Full Tilt Right 180 = Full Tilt Left Default = 60
int RA0= 120 +0;// Right Leg standing position; 0 = Full Tilt Right 180 = Full Tilt Left Default = 120
int LA1= 180; // Left Leg roll Position; 0 = Full Tilt Right 180 = Full Tilt Left Default = 170
int RA1= 0; // Right Leg roll position,0 = Full Tilt Right 180 = Full Tilt Left Default = 10
int LATL= LA0 +40; // Left Leg tilt left walking position,0 = Full Tilt Right 180 = Full Tilt Left Default = 90
int RATL= RA0 +60; // Right Leg tilt left walking position,0 = Full Tilt Right 180 = Full Tilt Left Default = 180
int LATR= LA0 -60; // Left Leg tilt right walking position,0 = Full Tilt Right 180 = Full Tilt Left Default = 0
int RATR= RA0 -40; // Right Leg tilt right walking position,0 = Full Tilt Right 180 = Full Tilt Left Default = 90
int LFFWRS=40; // Left foot forward walking rotation Speed; 0 = Slowest 90 = Fastest Default = 20
int RFFWRS=40 ; // Right foot forward walking rotation Speed; 0 = Slowest 90 = Fastest Default = 20
int LFBWRS= 40; // Left foot Backward walking rotation Speed; 0 = Slowest 90 = Fastest Default = 20
int RFBWRS= 40; // Right foot Backward walking rotation Speed; 0 = Slowest 90 = Fastest Default = 20
void NinjaHome()
{
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoHead.attach(ServoHeadPin, 544, 2400);
myservoLeftArm.write(180);
myservoRightArm.write(0);
myservoHead.write(90);
delay(400);
myservoLeftFoot.write(90);
myservoRightFoot.write(90);
myservoLeftLeg.write(60);
myservoRightLeg.write(120);
delay(400);
myservoLeftLeg.detach();
myservoRightLeg.detach();
myservoLeftArm.detach();
myservoRightArm.detach();
myservoHead.detach();
}
void NinjaSetWalk()
{
myservoLeftArm.attach(ServoLeftArmPin, 544, 2400);
myservoRightArm.attach(ServoRightArmPin, 544, 2400);
myservoLeftArm.write(90);
myservoRightArm.write(90);
delay(200);
myservoLeftArm.detach();
myservoRightArm.detach();
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoLeftLeg.write(LA0);
myservoRightLeg.write(RA0);
delay(300);
myservoLeftLeg.detach();
myservoRightLeg.detach();
myservoLeftArm.attach(ServoLeftArmPin, 544, 2400);
myservoRightArm.attach(ServoRightArmPin, 544, 2400);
myservoLeftArm.write(180);
myservoRightArm.write(0);
delay(300);
myservoLeftArm.detach();
myservoRightArm.detach();
}
void NinjaWalkForward()
{
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoLeftLeg.write(LATR);
myservoRightLeg.write(RATR);
delay(300);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoRightFoot.write(90-RFFWRS);
delay(300);
myservoRightFoot.detach();
delay(100);
myservoLeftLeg.write(LATL);
myservoRightLeg.write(RATL);
delay(300);
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoLeftFoot.write(90+LFFWRS);
delay(300);
myservoLeftFoot.detach();
delay(100);
}
void NinjaWalkBackward()
{
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoLeftLeg.write(LATR);
myservoRightLeg.write(RATR);
delay(300);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoRightFoot.write(90+RFFWRS);
delay(300);
myservoRightFoot.detach();
delay(100);
myservoLeftLeg.write(LATL);
myservoRightLeg.write(RATL);
delay(300);
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoLeftFoot.write(90-LFFWRS);
delay(300);
myservoLeftFoot.detach();
delay(100);
}
void NinjaWalkLeft()
{
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoLeftLeg.write(LATR);
myservoRightLeg.write(RATR);
delay(300);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoRightFoot.write(90-RFFWRS);
delay(50);
myservoRightFoot.detach();
delay(100);
myservoLeftLeg.write(LATL);
myservoRightLeg.write(RATL);
delay(300);
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoLeftFoot.write(90+LFFWRS);
delay(300);
myservoLeftFoot.detach();
delay(100);
}
void NinjaWalkRight()
{
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoLeftLeg.write(LATR);
myservoRightLeg.write(RATR);
delay(300);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoRightFoot.write(90-RFFWRS);
delay(300);
myservoRightFoot.detach();
delay(100);
myservoLeftLeg.write(LATL);
myservoRightLeg.write(RATL);
delay(300);
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoLeftFoot.write(90+LFFWRS);
delay(50);
myservoLeftFoot.detach();
delay(100);
}
void NinjaWalkStop()
{myservoLeftFoot.write(90);
myservoRightFoot.write(90);
myservoLeftLeg.write(LA0);
myservoRightLeg.write(RA0);}
void NinjaSetRoll()
{myservoLeftArm.attach(ServoLeftArmPin, 544, 2400);
myservoRightArm.attach(ServoRightArmPin, 544, 2400);
myservoLeftArm.write(90);myservoRightArm.write(90);
delay(200);
myservoLeftArm.detach();myservoRightArm.detach();
myservoLeftLeg.attach(ServoLeftLegPin, 544, 2400);
myservoRightLeg.attach(ServoRightLegPin, 544, 2400);
myservoLeftLeg.write(LA1);
myservoRightLeg.write(RA1);
delay(300);
myservoLeftLeg.detach();myservoRightLeg.detach();
myservoLeftArm.attach(ServoLeftArmPin, 544, 2400);
myservoRightArm.attach(ServoRightArmPin, 544, 2400);
myservoLeftArm.write(180);myservoRightArm.write(0);
delay(300);
myservoLeftArm.detach();myservoRightArm.detach();}
void NinjaRollForward(int speed)
{
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoLeftFoot.write(90 + speed);
myservoRightFoot.write(90 - speed);
}
void NinjaRollBackward(int speed)
{
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoLeftFoot.write(90 - speed);
myservoRightFoot.write(90 + speed);
}
void NinjaRollLeft(int speed)
{
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoLeftFoot.write(90 - speed);
myservoRightFoot.write(90 - speed);
}
void NinjaRollRight(int speed)
{
myservoLeftFoot.attach(ServoLeftFootPin, 544, 2400);
myservoRightFoot.attach(ServoRightFootPin, 544, 2400);
myservoLeftFoot.write(90 + speed);
myservoRightFoot.write(90 + speed);
}
void setup() {
}
void loop() {
NinjaHome();
NinjaSetWalk();
for (int count=0 ; count<5 ; count++) {
NinjaWalkForward();
delay(100);
NinjaWalkStop();
delay(500);
}
delay(2*1000);
NinjaSetRoll();
for (int count=0 ; count<5 ; count++) {
NinjaRollRight(map(50, 0, 100, 0, 90));
}
delay(2*1000);
}
|
沒有留言:
張貼留言