update
This commit is contained in:
parent
f0b0f370cc
commit
48a302e9f0
3 changed files with 81 additions and 19 deletions
37
arduino/catchrobo2012/WiiNun.cpp
Executable file
37
arduino/catchrobo2012/WiiNun.cpp
Executable file
|
@ -0,0 +1,37 @@
|
|||
/*
|
||||
WiiNun.cpp
|
||||
(c)2012 kou029w - MIT License [http://kou029w.appspot.com/mit-license.txt]
|
||||
*/
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include <Arduino.h>
|
||||
#else
|
||||
#include <WProgram.h>
|
||||
#endif
|
||||
#include <Wire.h>
|
||||
#include "WiiNun.h"
|
||||
|
||||
void WiiNun::begin(){
|
||||
Wire.begin();
|
||||
Wire.beginTransmission(0x52);
|
||||
Wire.write(0x40); // sends memory address
|
||||
Wire.write(0x00);
|
||||
Wire.endTransmission();
|
||||
}
|
||||
|
||||
byte WiiNun::_decodeByte(byte x){
|
||||
x = (x ^ 0x17) + 0x17;
|
||||
return x;
|
||||
}
|
||||
|
||||
void WiiNun::get(){
|
||||
byte i=0;
|
||||
Wire.requestFrom(0x52, 6);
|
||||
while(Wire.available() || i<6){
|
||||
WiiNun::data[i] = WiiNun::_decodeByte(Wire.read());
|
||||
i++;
|
||||
}
|
||||
Wire.beginTransmission(0x52);
|
||||
Wire.write(0x00);
|
||||
Wire.endTransmission();
|
||||
}
|
25
arduino/catchrobo2012/WiiNun.h
Executable file
25
arduino/catchrobo2012/WiiNun.h
Executable file
|
@ -0,0 +1,25 @@
|
|||
/*
|
||||
WiiNun.h
|
||||
(c)2012 kou029w - MIT License [http://kou029w.appspot.com/mit-license.txt]
|
||||
*/
|
||||
|
||||
#ifndef WiiNun_h
|
||||
#define WiiNun_h
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include <Arduino.h>
|
||||
#else
|
||||
#include <WProgram.h>
|
||||
#endif
|
||||
#include <Wire.h>
|
||||
|
||||
class WiiNun{
|
||||
public:
|
||||
byte data[6];
|
||||
void begin();
|
||||
void get();
|
||||
private:
|
||||
byte _decodeByte(byte x);
|
||||
};
|
||||
|
||||
#endif
|
38
arduino/catchrobo2012/catchrobo2012.ino
Normal file → Executable file
38
arduino/catchrobo2012/catchrobo2012.ino
Normal file → Executable file
|
@ -1,6 +1,6 @@
|
|||
#include <Servo.h>
|
||||
#include <Wire.h>
|
||||
#include <WiiNun.h>
|
||||
#include "WiiNun.h"
|
||||
#include "Motor.h"
|
||||
|
||||
#define PIN_LED 13
|
||||
|
@ -18,7 +18,7 @@
|
|||
|
||||
Servo base;
|
||||
Servo catcher;
|
||||
WiiNun wiiNun;
|
||||
WiiNun WiiNun;
|
||||
Motor horMotor;
|
||||
Motor verMotor;
|
||||
|
||||
|
@ -29,7 +29,7 @@ void setup(){
|
|||
digitalWrite(PIN_GND, LOW);
|
||||
delay(100);
|
||||
// Serial.begin(19200);
|
||||
wiiNun.begin();
|
||||
WiiNun.begin();
|
||||
base.attach(PIN_SERVO_BASE);
|
||||
catcher.attach(PIN_SERVO_CATCHER);
|
||||
pinMode(PIN_LED, OUTPUT);
|
||||
|
@ -39,20 +39,20 @@ void setup(){
|
|||
|
||||
void loop(){
|
||||
// ヌンチャクを読む
|
||||
wiiNun.get();
|
||||
byte joyx = wiiNun.data[0];
|
||||
byte joyy = wiiNun.data[1];
|
||||
byte accx = wiiNun.data[2];
|
||||
byte accy = wiiNun.data[3];
|
||||
byte accz = wiiNun.data[4];
|
||||
byte zbut = ((~wiiNun.data[5] >> 0) & 1);
|
||||
byte cbut = ((~wiiNun.data[5] >> 1) & 1);
|
||||
if((wiiNun.data[5] >> 2) & 1) accx += 2;
|
||||
if((wiiNun.data[5] >> 3) & 1) accx += 1;
|
||||
if((wiiNun.data[5] >> 4) & 1) accy += 2;
|
||||
if((wiiNun.data[5] >> 5) & 1) accy += 1;
|
||||
if((wiiNun.data[5] >> 6) & 1) accz += 2;
|
||||
if((wiiNun.data[5] >> 7) & 1) accz += 1;
|
||||
WiiNun.get();
|
||||
byte joyx = WiiNun.data[0];
|
||||
byte joyy = WiiNun.data[1];
|
||||
byte accx = WiiNun.data[2];
|
||||
byte accy = WiiNun.data[3];
|
||||
byte accz = WiiNun.data[4];
|
||||
byte zbut = ((~WiiNun.data[5] >> 0) & 1);
|
||||
byte cbut = ((~WiiNun.data[5] >> 1) & 1);
|
||||
if((WiiNun.data[5] >> 2) & 1) accx += 2;
|
||||
if((WiiNun.data[5] >> 3) & 1) accx += 1;
|
||||
if((WiiNun.data[5] >> 4) & 1) accy += 2;
|
||||
if((WiiNun.data[5] >> 5) & 1) accy += 1;
|
||||
if((WiiNun.data[5] >> 6) & 1) accz += 2;
|
||||
if((WiiNun.data[5] >> 7) & 1) accz += 1;
|
||||
// ヌンチャクおわり
|
||||
|
||||
char x = (char)(joyx-0x7F); // スティックの中心を0にする
|
||||
|
@ -80,9 +80,9 @@ void loop(){
|
|||
else if(ay < -0x10) verMotor.speed(-0xCC);
|
||||
else verMotor.mode(STOP);
|
||||
|
||||
byte catcherDeg = 100;
|
||||
byte catcherDeg = 135;
|
||||
if(cbut){ // cボタン押すとキャッチャーを離す
|
||||
catcherDeg = 30;
|
||||
catcherDeg = 45;
|
||||
}
|
||||
catcher.write(catcherDeg);
|
||||
|
||||
|
|
Loading…
Add table
Reference in a new issue