/* PS3BT_arduino_tank_2dcmotor_TB6612_FIRE_C2 モータドライバはTB6612 3ピンでサーボモータ(砲身上下)を動かす Ver.3 砲塔旋回モータを追加 砲撃時のリコイルアクション+LED点灯、銃撃時のLED点滅(5回)の機能を追加 出力8本のGPIOを使用し、LED点灯をさせる */
#include #include #ifdef dobogusinclude #include #endif #include // needed by Arduino IDE #include MaxGPIO max; //#include //Servo myservo; #include VarSpeedServo myservo; int servo_pos = 90; const int servo_sp = 50; const int d_time = 20; int ch = 0; int val = 0; int pos_y; int pos_x; int PWMA = 5; // ← 11 Aモータ PWM 左側モータ int AIN1 = 4; // ← 9 Aモータ IN1 ( 9ピンはUSBホストシールド使用 int AIN2 = 2; // ← 8 Aモータ IN2 int BIN1 = 8; // ← 7 Bモータ IN1 int BIN2 = 7; // ← 6 Bモータ IN2 int PWMB = 6; // ← 10 Bモータ PWM 右側モータ ( 10ピンはUSBホストシールド使用
int motor_speed; const int motor_sp1 = 128; //超信地旋回速度 const int motor_sp0 = 255; //超高速
USB Usb; BTD Btd(&Usb); //そうしたBluetooth Dongleの事例を作成する必要があります PS3BT PS3(&Btd); //これで事例が作成されます //PS3BT PS3(&Btd, 0x00, 0x15, 0x83, 0x3D, 0x0A, 0x57); // これにはBluetoothアドレスも格納されます // これはスケッチを実行するときにドングルから取得できます
void setup() { pinMode(PWMA, OUTPUT); pinMode(AIN1, OUTPUT); pinMode(AIN2, OUTPUT); pinMode(BIN1, OUTPUT); pinMode(BIN2, OUTPUT); pinMode(PWMB, OUTPUT);
myservo.attach(3); //servo1 ピン3 (9-11ピンは使えない) myservo.write(servo_pos);
Serial.begin(115200); while (!Serial); // Wait for serial port to connect - used on Leonardo, Teensy and other boards with built-in USB CDC serial connection if (Usb.Init() == -1) { Serial.print(F("\r\nOSC did not start")); while (1); //halt } Serial.print(F("\r\nPS3 Bluetooth Library Started")); }
void loop() { Usb.Task(); if (PS3.PS3Connected) { //スティックの中央は127だけどピタリと止まらないので+-10ほど余裕を持たせる。 //左スティック上下の値(最上部0、中央127、最下部255)を読み込む pos_y = PS3.getAnalogHat(LeftHatY); pos_x = PS3.getAnalogHat(LeftHatX);
/* 砲身 UP/DOWN スティックが下(20未満)の時は1ずつ下に動く。 スティックが上(235より上)の時1ずつ上に動く。 スティックを中間に戻すと、サーボはその位置で停止。 ボタン(SQUARE)を押すと90°にセット。 */ if ((PS3.getAnalogHat(RightHatY) < 20) && (servo_pos < 179 )) { // UP servo_pos++; myservo.write(servo_pos, servo_sp, true); }
if ((PS3.getAnalogHat(RightHatY) > 235) && (servo_pos > 1 )) { //DOWN servo_pos--; myservo.write(servo_pos, servo_sp, true); }
if (PS3.getButtonClick(SQUARE)) { //90° servo_pos = 90; myservo.write(servo_pos, servo_sp, true); delay(d_time); }
//砲塔旋回 if (PS3.getAnalogHat(RightHatX) > 235) { //右旋回 max.write(5, HIGH); max.write(6, LOW); } else if (PS3.getAnalogHat(RightHatX) < 20) { //左旋回 max.write(5, LOW); max.write(6, HIGH); } else { //停止 max.write(5, LOW); max.write(6, LOW); }
//砲撃 //リコイル if (PS3.getButtonClick(R1) && ch == 0 ) { Serial.println("FIRE"); max.write(0, HIGH); digitalWrite(AIN1, LOW); digitalWrite(AIN2, HIGH); analogWrite(PWMA, motor_sp0); digitalWrite(BIN1, LOW); digitalWrite(BIN2, HIGH); analogWrite(PWMB, motor_sp0); ch = 20000; //約5秒間は砲撃不可 delay(70);
digitalWrite(AIN1, LOW); digitalWrite(AIN2, LOW); analogWrite(PWMA, 0); digitalWrite(BIN1, LOW); digitalWrite(BIN2, LOW); analogWrite(PWMA, 0); delay(20);
max.write(0, LOW); digitalWrite(AIN1, HIGH); digitalWrite(AIN2, LOW); analogWrite(PWMA, motor_sp1); digitalWrite(BIN1, HIGH); digitalWrite(BIN2, LOW); analogWrite(PWMB, motor_sp1); delay(130); } else { if (ch > 0) { ch--; max.write(3, HIGH); //装填中 } else { max.write(3, LOW); //砲撃可 } }
//銃撃 if ( PS3.getButtonClick(L1)) { for ( int i = 0; i < 5 ; i++) { val++; Serial.print("L1 : "); Serial.println(PS3.getButtonClick(L1)); Serial.println("DA "); Serial.println(val); max.write(1, HIGH); delay(50); max.write(1, LOW); delay(50); Serial.println(""); } }
//ヘッドライト if (PS3.getButtonClick(RIGHT)) { //点灯 max.write(7, HIGH); }
if (PS3.getButtonClick(LEFT)) { //消灯 max.write(7, LOW); }
//左スティックがセンター付近は停止(ブレーキ) if (pos_x >= 117 && pos_x <= 137 && pos_y >= 117 && pos_y <= 137) { digitalWrite(AIN1, HIGH); digitalWrite(AIN2, HIGH); analogWrite(PWMA, 0); digitalWrite(BIN1, HIGH); digitalWrite(BIN2, HIGH); analogWrite(PWMA, 0); max.write(2, HIGH); //ブレーキランプ点灯 }
//前進 else if (pos_y < 117 && pos_x > 117 && pos_x < 137) { //左スティック中央(127)から最上部(0)の値をモーターのスピード0から255に変換 motor_speed = map(pos_y, 117, 0, 0, 255); digitalWrite(AIN1, HIGH); digitalWrite(AIN2, LOW); analogWrite(PWMA, motor_speed); digitalWrite(BIN1, HIGH); digitalWrite(BIN2, LOW); analogWrite(PWMB, motor_speed); max.write(2, LOW); }
//後進 else if ( pos_y > 137 && pos_x > 117 && pos_x < 137) { motor_speed = map(pos_y, 137, 255, 0, 255); digitalWrite(AIN1, LOW); digitalWrite(AIN2, HIGH); analogWrite(PWMA, motor_speed); digitalWrite(BIN1, LOW); digitalWrite(BIN2, HIGH); analogWrite(PWMB, motor_speed); max.write(2, LOW); }
//前進右旋回 else if ( pos_y < 117 && pos_x > 137) { motor_speed = map(pos_y, 117, 0, 0, 255); digitalWrite(AIN1, HIGH); digitalWrite(AIN2, LOW); analogWrite(PWMA, motor_speed); digitalWrite(BIN1, LOW); digitalWrite(BIN2, LOW); analogWrite(PWMB, motor_speed); max.write(2, LOW); }
//前進左旋回 else if ( pos_y < 117 && pos_x < 117) { motor_speed = map(pos_y, 117, 0, 0, 255); digitalWrite(AIN1, LOW); digitalWrite(AIN2, LOW); analogWrite(PWMA, motor_speed); digitalWrite(BIN1, HIGH); digitalWrite(BIN2, LOW); analogWrite(PWMB, motor_speed); max.write(2, LOW); }
//後進右旋回 else if ( pos_y > 137 && pos_x > 137) { motor_speed = map(pos_y, 137, 255, 0, 255); digitalWrite(AIN1, LOW); digitalWrite(AIN2, HIGH); analogWrite(PWMA, motor_speed); digitalWrite(BIN1, LOW); digitalWrite(BIN2, LOW); analogWrite(PWMB, motor_speed); max.write(2, LOW); }
//後進左旋回 else if ( pos_y > 137 && pos_x < 117) { motor_speed = map(pos_y, 117, 0, 0, 255); digitalWrite(AIN1, LOW); digitalWrite(AIN2, LOW); analogWrite(PWMA, motor_speed); digitalWrite(BIN1, LOW); digitalWrite(BIN2, HIGH); analogWrite(PWMB, motor_speed); max.write(2, LOW); }
//右超信地旋回 else if ( pos_y > 117 && pos_y < 137 && pos_x > 137) { digitalWrite(AIN1, HIGH); digitalWrite(AIN2, LOW); analogWrite(PWMA, motor_sp1); digitalWrite(BIN1, LOW); digitalWrite(BIN2, HIGH); analogWrite(PWMB, motor_sp1); max.write(2, LOW); }
//左超信地旋回 else if ( pos_y > 117 && pos_y < 137 && pos_x < 117) { digitalWrite(AIN1, LOW); digitalWrite(AIN2, HIGH); analogWrite(PWMA, motor_sp1); digitalWrite(BIN1, HIGH); digitalWrite(BIN2, LOW); analogWrite(PWMB, motor_sp1); max.write(2, LOW); } } }
|