リクエストが有りましたので、T34のスケッチと回路図を公開します。
久しぶりにT34を動かしてみて、気になるところを変更して動作を確認しました。
▼先日のスケッチに手を入れ変更後のスケッチを公開します。
2024-09-12 更新 IRremote Ver.2.2.3より2.8.0の方が安定しています。
メモリー容量ギリギリなのでIDEやライブラリのバージョンを調整しました。
- /* PS3BT_arduino_NANO_tank_TB6612_IRw_MP3_T34spec3c
- 2024-09-11
- 砲塔旋回サーボ停止追加 detach()
- モータドライバはTB6612
- 砲撃時のリコイルアクション
- irremote PIN3 赤外線発光(砲撃)システム
- A0ピンに赤外線受光モジュール出力を接続し、被弾処理を追加
- 主砲発光はミニUSBシールドのGPOUTピン0を使用
- 機銃主砲発光はミニUSBシールドのGPOUTピン1を使用
- ヘッドライトはミニUSBシールドのGPOUTピン2を使用
- MP3プレーヤーで効果音を発生
- 開発環境
- Arduino 1.8.19
- IRremote Ver.2.8.0
- DFRobotDFPlayerMini.h 1.0.5
- USBホストシールド 2.0 1.20
- スケッチが使用できるメモリが少なくなっています。動作が不安定になる可能性があります。
- 最大30720バイトのフラッシュメモリのうち、スケッチが30282バイト(98%)を使っています。
- 最大2048バイトのRAMのうち、グローバル変数が1626バイト(79%)を使っていて、
- ローカル変数で422バイト使うことができます。
-
- */
- #include <SoftwareSerial.h>
- #include <DFRobotDFPlayerMini.h>
- SoftwareSerial mySerial(A2, A3); // DFPlayer TX,RX
- DFRobotDFPlayerMini myDFPlayer;
- #include <PS3BT.h>
- #include <usbhub.h>
- #ifdef dobogusinclude
- #include <spi4teensy3.h>
- #endif
- //#include <Usb.h> // needed by Arduino IDE
- #include <USB_Host_Shield_GPIO.h> // GPOUTピンで主砲LEDを発光させるため 1.20
- MaxGPIO max;
- USB Usb;
- BTD Btd(&Usb);
- PS3BT PS3(&Btd);
- //PS3BT PS3(&Btd, 0x00, 0x1B, 0xDC, 0xF2, 0x53, 0xFA); //for Dongke B
- /*シリアルモニタにBluetooth DongleのアドレスがSerial.printされる。
- 書き出された6個のコードをスケッチを変更し、
- ドングルを指した状態でArduinoに書き込む(電源は切らない)
- ドングルを抜いてUSBケーブルでPS3コントローラを接続する(電源は切らない)
- ケーブルを抜いてドングルを指し直す(Arduinoを再起動する)
- PS3コントローラのPS ボタンを押してペアリングする。
- */
- #include <IRremote.h>
- IRsend irsend;
- int RECV_PIN = A0 ; //赤外線受光部をPIN A0に
- IRrecv irrecv(RECV_PIN);
- decode_results results; //受信信号を格納する
- const long sign_hit = 0x4CB0FADD;
- int cnt = 0 ;
- #include <VarSpeedServo.h>
- VarSpeedServo myservo_1;
- VarSpeedServo myservo_2;
- int servo_1pos = 75;
- const int servo1_sp = 20;
- const int servo2_sp = 5;
- int ch = 0;
- int pos_y;
- int pos_x;
- int pos_ry;
- int pos_rx;
- int PWMA = 5; // Aモータ PWM 左側モータ
- int AIN1 = 4; // Aモータ IN1 ( 9ピンはUSBホストシールド使用
- int AIN2 = 2; // Aモータ IN2
- int BIN1 = 8; // Bモータ IN1
- int BIN2 = 7; // Bモータ IN2
- int PWMB = 6; // Bモータ PWM 右側モータ( 10ピンはUSBホストシールド使用
- int motor_speed;
- int steering;
- const int LED_3 = A1 ; //ブレーキランプ
- void setup() {
- irrecv.enableIRIn(); // Start the receiver
- pinMode(RECV_PIN, INPUT) ; // 赤外線受信モジュールに接続ピンをデジタル入力に設定
- pinMode(PWMA, OUTPUT);
- pinMode(AIN1, OUTPUT);
- pinMode(AIN2, OUTPUT);
- pinMode(BIN1, OUTPUT);
- pinMode(BIN2, OUTPUT);
- pinMode(PWMB, OUTPUT);
- pinMode(LED_3, OUTPUT);
- pinMode(A4, OUTPUT);
- pinMode(A5, OUTPUT);
- myservo_1.attach(A4); //servo1 砲身上下
- myservo_1.write(servo_1pos);
- myservo_1.detach();
- myservo_2.attach(A5); //servo2 砲塔旋回
- myservo_2.write(90);
- Serial.begin (115200);
- mySerial.begin (9600);
- myDFPlayer.begin(mySerial);
- myDFPlayer.volume(20); //Set volume value (0~30)
- 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) {
- if (irrecv.decode(&results)) { // 受信コードの値が
- if (results.value == sign_hit) { // 0x4CB0FADDだったら被弾
- Hit();
- }
- irrecv.resume();
- }
- //砲身 UP/DOWN
- if ( PS3.getButtonClick(R3)) { //CENTER
- myservo_1.attach(A4);
- myservo_1.write(servo_1pos, servo1_sp, true);
- // myservo_1.detach();
- }
- pos_ry = PS3.getAnalogHat(RightHatY);
- if (pos_ry < 10) { // UP
- myservo_1.attach(A4);
- myservo_1.write(servo_1pos - 30, servo1_sp, true);
- // myservo_1.detach();
- } else if (pos_ry > 245) { //DOWN
- myservo_1.attach(A4);
- myservo_1.write(servo_1pos + 30, servo1_sp, true);
- // myservo_1.detach();
- } else { //停止
- myservo_1.detach();
- }
- //砲塔旋回
- if ( PS3.getAnalogHat(LeftHatX) > 230) { //右旋回
- myservo_2.attach(A5);
- myservo_2.write(100, servo2_sp);
- } else if (PS3.getAnalogHat(LeftHatX) < 26) { //左旋回
- myservo_2.attach(A5);
- myservo_2.write(80, servo2_sp);
- } else { //停止
- //myservo_2.attach(A5);
- myservo_2.write(90, 255, true);
- myservo_2.detach();
- }
- //砲撃 + リコイル
- if (PS3.getButtonClick(R1) && ch == 0 ) {
- int khz = 38; // 38kHz carrier frequency for the NEC protocol
- unsigned int irSignal[] = {4100, 1000, 2000, 2050, 1000}; // vs BATTLE TANK jr T-72 40MHz
- // AnalysIR Batch Export (IRremote) - RAW
- irsend.sendRaw(irSignal, (sizeof(irSignal) / sizeof(irSignal[0])), khz);
- //irsend.sendRaw(data buf, length, hertz)
- irrecv.enableIRIn(); // 受信を再開する
- max.write(0, HIGH); //主砲発光
- myDFPlayer.play(15);
- delay(200);
- motor_run(128, 0, 1, 128, 0, 1, 1);
- ch = 5000; //約2秒間は砲撃不可
- delay(100);
- motor_run(0, 0, 0, 0, 0, 0, 1);
- delay(200);
- max.write(0, LOW);
- motor_run(64, 1, 0, 64, 1, 0, 1);
- delay(260);
- } else {
- if (ch > 0) {
- ch--;
- }
- }
- //銃撃
- if ( PS3.getButtonClick(L1)) {
- //mp3_play (10);
- myDFPlayer.play(10);
- delay(200);
- for ( int i = 0; i < 5 ; i++) {
- max.write(1, HIGH);
- delay(100);
- max.write(1, LOW);
- delay(80);
- }
- }
- //ヘッドライト
- if (PS3.getButtonClick(RIGHT)) { //点灯
- max.write(2, HIGH);
- } else if (PS3.getButtonClick(LEFT)) { //消灯
- max.write(2, LOW);
- }
- //走行コントロール
- pos_y = PS3.getAnalogHat(LeftHatY);
- pos_x = PS3.getAnalogHat(RightHatX);
- //前進
- if (pos_y <= 102 && pos_x >= 102 && pos_x <= 152) {
- motor_speed = map(pos_y, 102, 0, 0, 180);
- motor_run(motor_speed, 1, 0, motor_speed, 1, 0, 0);
- }
- //後進
- else if ( pos_y >= 152 && pos_x >= 102 && pos_x <= 152) {
- motor_speed = map(pos_y, 152, 255, 0, 180);
- motor_run(motor_speed, 0, 1, motor_speed, 0, 1, 0);
- }
- //前進右緩旋回、信地旋回
- else if ( pos_y <= 102 && pos_x > 152) {
- motor_speed = map(pos_y, 102, 0, 0, 180);
- steering = motor_speed * (1.00 - (map(pos_x, 152, 255, 0, 255) / 255.00));
- motor_run(motor_speed, 1, 0, steering, 1, 0, 0);
- }
- //前進左旋回、信地旋回
- else if ( pos_y < 102 && pos_x < 102) {
- motor_speed = map(pos_y, 102, 0, 0, 180);
- steering = motor_speed * (1.00 - (map(pos_x, 102, 0, 0, 255) / 255.00));
- motor_run(steering, 1, 0, motor_speed, 1, 0, 0);
- }
- //後進右旋回、信地旋回
- else if ( pos_y > 152 && pos_x > 152) {
- motor_speed = map(pos_y, 152, 255, 0, 180);
- steering = motor_speed * (1.00 - (map(pos_x, 152, 255, 0, 255) / 255.00));
- motor_run(motor_speed, 0, 1, steering, 0, 1, 0);
- }
- //後進左旋回、信地旋回
- else if ( pos_y > 152 && pos_x < 102) {
- motor_speed = map(pos_y, 152, 255, 0, 180);
- steering = motor_speed * (1.00 - (map(pos_x, 102, 0, 0, 255) / 255.00));
- motor_run(steering, 0, 1, motor_speed, 0, 1, 0);
- }
- //右超信地旋回
- else if ( pos_x > 245 && pos_y >= 102 && pos_y <= 152) {
- motor_speed = 90;
- motor_run(motor_speed, 1, 0, motor_speed, 0, 1, 0);
- }
- //左超信地旋回
- else if ( pos_x < 10 && pos_y >= 102 && pos_y <= 152) {
- motor_speed = 90;
- motor_run(motor_speed, 0, 1, motor_speed, 1, 0, 0);
- }
- else { //停止
- motor_run(0, 1, 1, 0, 1, 1, 1);
- }
- }
- }
- void motor_run(int D0, int D1, int D2, int D3, int D4, int D5, int D6) {
- /* D0 : モータスピード(左)
- D1 : モータA(左)CH1 , D2 : モータA(左)CH2 1 = HIGH / 0 = LOW
- D3 : モータスピード(右)
- D4 : モータB(右)CH1 , D5 : モータB(右)CH2 1 = HIGH / 0 = LOW
- D6 : LED_3 ON/OFF 1 = HIGH / 0 = LOW
- */
- analogWrite(PWMA, D0);
- digitalWrite(AIN1, D1);
- digitalWrite(AIN2, D2);
- analogWrite(PWMB, D3);
- digitalWrite(BIN1, D4);
- digitalWrite(BIN2, D5);
- digitalWrite(LED_3, D6);
- }
- // ====被弾====
- void Hit() {
- motor_run(255, 0, 1, 255, 1, 0, 0); //左超信地旋回
- delay(100);
- motor_run(0, 1, 1, 0, 1, 1, 1); //停止
- delay(50);
- motor_run(255, 1, 0, 255, 0, 1, 0); //右超信地旋回
- delay(100);
- motor_run(0, 1, 1, 0, 1, 1, 1); //停止
- delay(50);
- /*
- motor_run(128, 1, 0, 1, 0, 0); //前進
- delay(50);
- motor_run(0, 1, 1, 1, 1, 1); //停止
- delay(50);
- */
- cnt++;
- if ( cnt >= 5 ) {
- motor_run(0, 1, 1, 0, 1, 1, 0); //停止
- delay(30000); //復活までに30秒
- cnt = 0;
- } else {
- delay(1000);
- }
- }