update
This commit is contained in:
parent
c37c972d1e
commit
f0b0f370cc
1 changed files with 12 additions and 12 deletions
|
@ -32,7 +32,7 @@ void setup(){
|
||||||
wiiNun.begin();
|
wiiNun.begin();
|
||||||
base.attach(PIN_SERVO_BASE);
|
base.attach(PIN_SERVO_BASE);
|
||||||
catcher.attach(PIN_SERVO_CATCHER);
|
catcher.attach(PIN_SERVO_CATCHER);
|
||||||
pinMode(PIN_LED , OUTPUT);
|
pinMode(PIN_LED, OUTPUT);
|
||||||
horMotor.attach(PIN_MOTOR_HORIZON_1, PIN_MOTOR_HORIZON_2);
|
horMotor.attach(PIN_MOTOR_HORIZON_1, PIN_MOTOR_HORIZON_2);
|
||||||
verMotor.attach(PIN_MOTOR_VERTICAL_1, PIN_MOTOR_VERTICAL_2);
|
verMotor.attach(PIN_MOTOR_VERTICAL_1, PIN_MOTOR_VERTICAL_2);
|
||||||
}
|
}
|
||||||
|
@ -60,8 +60,7 @@ void loop(){
|
||||||
// char ax = (char)(accx-0x7F);
|
// char ax = (char)(accx-0x7F);
|
||||||
char ay = (char)(accy-0x7F); // 水平状態を0にする
|
char ay = (char)(accy-0x7F); // 水平状態を0にする
|
||||||
|
|
||||||
byte baseDeg = 90;
|
static byte baseDeg = 90;
|
||||||
byte catcherDeg = 90;
|
|
||||||
if(zbut){ // zボタン押しながら
|
if(zbut){ // zボタン押しながら
|
||||||
digitalWrite(PIN_LED, HIGH);
|
digitalWrite(PIN_LED, HIGH);
|
||||||
if(y>0x1F) baseDeg = 180 - atan2(y, x)*180/PI; // 台座をスティックの角度にする
|
if(y>0x1F) baseDeg = 180 - atan2(y, x)*180/PI; // 台座をスティックの角度にする
|
||||||
|
@ -69,22 +68,23 @@ void loop(){
|
||||||
else if(baseDeg > 170) baseDeg = 170;
|
else if(baseDeg > 170) baseDeg = 170;
|
||||||
}else{ // zボタン離しながら
|
}else{ // zボタン離しながら
|
||||||
digitalWrite(PIN_LED, LOW);
|
digitalWrite(PIN_LED, LOW);
|
||||||
horMotor.speed(y);
|
horMotor.speed(y*2);
|
||||||
baseDeg += x/32; // 台座をxに応じて相対移動
|
baseDeg += x/32; // 台座をxに応じて相対移動
|
||||||
}
|
}
|
||||||
|
base.write(baseDeg);
|
||||||
|
|
||||||
if(0);
|
if(0);
|
||||||
else if(ay > +0x20) verMotor.mode(GO);
|
else if(ay > +0x20) verMotor.mode(GO);
|
||||||
else if(ay > +0x10) verMotor.speed(+0xCC);
|
else if(ay > +0x10) verMotor.speed(+0xCC);
|
||||||
else if(ay < -0x10) verMotor.speed(-0xCC);
|
|
||||||
else if(ay < -0x20) verMotor.mode(BACK);
|
else if(ay < -0x20) verMotor.mode(BACK);
|
||||||
|
else if(ay < -0x10) verMotor.speed(-0xCC);
|
||||||
|
else verMotor.mode(STOP);
|
||||||
|
|
||||||
catcherDeg = 90;
|
byte catcherDeg = 100;
|
||||||
if(cbut){ // cボタン押すとキャッチャーを離す
|
if(cbut){ // cボタン押すとキャッチャーを離す
|
||||||
catcherDeg = 15;
|
catcherDeg = 30;
|
||||||
}
|
}
|
||||||
|
|
||||||
base.write(baseDeg);
|
|
||||||
catcher.write(catcherDeg);
|
catcher.write(catcherDeg);
|
||||||
delay(10);
|
|
||||||
|
delay(50);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Reference in a new issue