2024-11-28
デカールが乾いたので艶消しクリアーを吹き、ウェザリングは程々にして完成としました。
▼完成動画もアップしました。
▼回路図
▼スケッチ
- /*PS3_ESP32_tank_MP3_DRV8835_GUNTANK_v1.5
- 2024-11-27
- 「ガンタンク発進します」音声追加。
- 「シャーッ」音声追加。
- サーボギヤ変更により回転角を広げる。
- 最大1310720バイトのフラッシュメモリのうち、スケッチが1088181バイト(83%)を使っています。
- 最大327680バイトのRAMのうち、グローバル変数が39564バイト(12%)を使っていて、
- ローカル変数で288116バイト使うことができます。
- 【書込み実行手順】
- AE-ESP32ボードの「BOOTボタン」ON しながら
- 「ENボタン」ON → OFF。
- 「BOOTボタン」OFF。
- Arduino IDE→「スケッチ」→「マイコンボードに書き込む」
- 書き込みが終わってもまだ実行はしない。
- 「ENボタン」ONで、実行(LED点滅)する。
- 効果音はDFPlayer Mini
- モータドライバはDRX8835
- 【ペアリング操作手順】
- PSボタンでペアリング開始。白色インジケータランプ高速点滅。
- 戦車の電源投入。
- インジケータランプ青色点灯でペアリング完了。
- 【走行コントロール】
- コントローラーの左スティック上下で前後進、
- 右スティックの左右でステアリングを制御。
- ステアリングを振っていくと回転軸側が減速していき(緩旋回から信地旋回)、
- 一杯に倒すと回転軸側は停止。(信地旋回)
- 左スティック中央で右ステアリングを一杯に振ると超信地旋回(速度50%)
- 【砲身上下】右十字キーの △と?ボタンで砲身上下。□ボタンでセンター。
- 【機関砲】 R1ボタンで主砲発射
- 【機銃】 L1ボタンで射撃(連射)
- 【効果音】左十字キーrightで「ガンタンク発進します」、leftで「シャーッ」
- */
- #include <Arduino.h> // Arduino ヘッダインクルード
- #include "SoftwareSerial.h" // EspSoftwareSerial
- #include "DFRobotDFPlayerMini.h"
- //SoftwareSerial mySoftwareSerial(16, 17); // RX, TX EspSoftwareSerial
- HardwareSerial Serial_df(2); // use HardwareSerial UART2 (16pin=RX, 17pin=TX)
- DFRobotDFPlayerMini myDFPlayer;
- void printDetail(uint8_t type, int value);
- #include <Ps3Controller.h>
- #include <ESP32Servo.h>
- Servo servo1; // create four servo objects
- int servo1Pin = 27;
- int LED_3 = 19; //キャノン砲
- int LED_4 = 18; //ミサイルランチャー
- int k = 0;
- int s = 0;
- int d_time = 50;
- int angle_servo1 = 90; // 上下center
- int dtime = 20; //砲身上下スピード(遅延時間)
- int anglenow = angle_servo1 ;
- int motor_speed;
- float steering;
- int pos_ly;
- int pos_lx;
- int pos_ry;
- int pos_rx;
- int AIN1 = 32; // A入力1/APHASE 左モータ AIN1
- int BIN1 = 25; // B入力1/BPHASE 右モータ BIN1
- int PWMApin = A5; // A入力2/AENABLE 左モータ AIN2 IO33
- int PWMBpin = A19; // B入力2/BENABLE 右モータ BIN2 IO26 (IO0は起動時不安定)
- int PWMA = 2; //PWMAチャンネル 0=NG 1=NG 0〜15
- int PWMB = 3; //PWMBチャンネル 0=NG 1=NG 0〜15
- void setup() {
- servo1.setPeriodHertz(50); // Standard 50hz servo PWMサイクル:20mS FS0307 120°
- servo1.attach(servo1Pin, 900, 2100); // (servo1Pin, minUs, maxUs)
- //delay(50);
- //mySoftwareSerial.begin(9600);
- Serial_df.begin(9600); // RX2 = 16, TX2 = 17
- Serial.begin(116500);
- //Ps3.begin("00:11:22:33:44:55"); //SixaxisPairToolで調べたmac adresに修正
- Ps3.begin("01:02:03:04:05:06"); // PS3コントローラmac address
- Serial.println("PS3 Ready");
- //if (!myDFPlayer.begin(mySoftwareSerial)) { //Use softwareSerial to communicate with mp3.
- if (!myDFPlayer.begin(Serial_df)) { //Use HardwareSerial to communicate with mp3.
- Serial.println(F("Unable to begin:"));
- Serial.println(F("1.Please recheck the connection!"));
- Serial.println(F("2.Please insert the SD card!"));
- while (true) {
- delay(0); // Code to compatible with ESP8266 watch dog.
- }
- }
- Serial.println(F("DFPlayer Mini online."));
- myDFPlayer.volume(20); //Set volume value. From 0 to 30
- ledcSetup(PWMA, 5000, 8); //チャンネル,周波数,解像度(8bit=256段階)
- ledcAttachPin(PWMApin, PWMA); //ledPinをPWMCHチャンネルに接続
- ledcSetup(PWMB, 5000, 8); //チャンネル,周波数,解像度(8bit=256段階)
- ledcAttachPin(PWMBpin, PWMB); //ledPinをPWMCHチャンネルに接続
- pinMode(AIN1, OUTPUT);
- pinMode(BIN1, OUTPUT);
- pinMode(LED_3, OUTPUT);
- pinMode(LED_4, OUTPUT);
- servo1.write(angle_servo1); // 0 - 180
- delay(100);
- myDFPlayer.play(5); //ガンタンク発進
- delay( 1000);
- }
- void loop() {
- if (Ps3.isConnected()) {
- pos_lx = Ps3.data.analog.stick.lx;
- pos_lx = pos_lx + 128;
- pos_ly = Ps3.data.analog.stick.ly;
- pos_ly = pos_ly + 128;
- pos_rx = Ps3.data.analog.stick.rx;
- pos_rx = pos_rx + 128;
- if ( Ps3.event.button_down.right) { // ガンタンク発進します
- myDFPlayer.play(5);
- delay(1000);
- }
- if ( Ps3.event.button_down.left) { // シャーッ
- myDFPlayer.play(3);
- delay(1000);
- }
- //砲身上下
- if ( Ps3.event.button_down.square) { // center
- if (anglenow > angle_servo1) {
- for (anglenow = anglenow; anglenow >= angle_servo1; anglenow -= 1) {
- servo1.write(anglenow);
- delay(dtime);
- }
- }
- else {
- for (anglenow = anglenow; anglenow <= angle_servo1; anglenow += 1) {
- servo1.write(anglenow);
- delay(dtime);
- }
- }
- }
- if ( Ps3.event.button_down.triangle) { // up
- for (anglenow = anglenow; anglenow >= (angle_servo1 - 60); anglenow -= 1 ) {
- servo1.write(anglenow);
- delay(dtime);
- }
- }
- if ( Ps3.event.button_down.cross) { // down
- for (anglenow = anglenow; anglenow < (angle_servo1 + 60); anglenow += 1 ) {
- servo1.write(anglenow);
- delay(dtime);
- }
- }
- if (Ps3.event.button_down.r1) { //キャノン砲
- digitalWrite(LED_3, HIGH); //発光
- myDFPlayer.play(4);
- delay(200);
- motor_run(180, 1, 180, 1); // 車体リコイル
- delay(150);
- motor_run(0, 0, 0, 0);
- delay(200);
- digitalWrite(LED_3, LOW);
- motor_run(90, 0, 90, 0);
- delay(300);
- }
- if (Ps3.event.button_down.l1) { //ミサイルランチャー
- myDFPlayer.play(2);
- delay(100);
- for ( k = 0; k < 9; k++) {
- digitalWrite(LED_4, HIGH); //発光
- delay(80);
- digitalWrite(LED_4, LOW);
- delay(160);
- }
- }
- //前進
- if (pos_ly <= 89 && pos_rx >= 89 && pos_rx <= 165) {
- motor_speed = map(pos_ly, 89, 0, 0, 255);
- motor_run(motor_speed, 0, motor_speed, 0);
- }
- //後進
- else if ( pos_ly >= 165 && pos_rx >= 89 && pos_rx <= 165) {
- motor_speed = map(pos_ly, 165, 255, 0, 255) ;
- motor_run(motor_speed, 1, motor_speed, 1);
- }
- //前進右緩旋回、信地旋回
- //else if ( pos_ly <= 89 && pos_rx > 165 && pos_rx <= 245) {
- else if ( pos_ly <= 89 && pos_rx >= 165) {
- motor_speed = map(pos_ly, 89, 0, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_rx, 165, 255, 0, 255) / 255.00));
- motor_run(motor_speed, 0, steering, 0);
- }
- //前進左緩旋回、信地旋回
- //else if ( pos_ly <= 89 && pos_rx < 89 && pos_rx >= 10) {
- else if ( pos_ly <= 89 && pos_rx <= 89) {
- motor_speed = map(pos_ly, 89, 0, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_rx, 89, 0, 0, 255) / 255.00));
- motor_run(steering, 0, motor_speed, 0);
- }
- //後進右緩旋回、信地旋回
- //else if ( pos_ly >= 165 && pos_rx > 165 && pos_rx <= 245) {
- else if ( pos_ly >= 165 && pos_rx >= 165 ) {
- motor_speed = map(pos_ly, 165, 255, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_rx, 165, 255, 0, 255) / 255.00));
- motor_run(motor_speed, 1, steering, 1);
- }
- //後進左緩旋回、信地旋回
- //else if ( pos_ly >= 165 && pos_rx < 89 && pos_rx >= 10) {
- else if ( pos_ly >= 165 && pos_rx <= 89 ) {
- motor_speed = map(pos_ly, 165, 255, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_rx, 89, 0, 0, 255) / 255.00));
- motor_run(steering, 1, motor_speed, 1);
- }
- //右超信地旋回
- else if (pos_rx >= 245 && pos_ly >= 89 && pos_ly <= 165) {
- motor_speed = 204;
- motor_run(motor_speed, 0, motor_speed, 1);
- }
- //左超信地旋回
- else if (pos_rx <= 10 && pos_ly >= 89 && pos_ly <= 165) {
- motor_speed = 204;
- motor_run(motor_speed, 1, motor_speed, 0);
- }
- else { //停止(ブレーキ)
- motor_run(0, 0, 0, 0);
- }
- }
- }
- void motor_run(int D0, int D1, int D2, int D3) {
- //D0 : モータスピード(左)
- //D1 : モータA(左)1 = HIGH / 0 = LOW
- //D2 : モータスピード(右)
- //D3 : モータB(右)1 = HIGH / 0 = LOW
- //analogWrite(PWMA, D0);
- ledcWrite(PWMA, D0); //(チャンネル,解像度)
- digitalWrite(AIN1, D1);
- //analogWrite(PWMB, D2);
- ledcWrite(PWMB, D2); //(チャンネル,解像度)
- digitalWrite(BIN1, D3);
- }
最後までお付き合い頂き、ありがとうございました。
次回作も、よろしく。