2025-02-04
主砲の旋回範囲を微調整し、アクリファイバーの不要分を切除して完成です。
完成画像、動画は後日にアップします。
今日はESP32用スケッチ(プログラム)と回路図を掲載します。
サーボモータの動作範囲はセンター90°、左右45°(45°~135°)としていましたが、
車体に組み込んで10°程度設定を調整しました。
【スケッチ】
- /*PS3_ESP32_tank_MP3_JQ8400_MK4_v1a
- 2025-02-04
- 最大1310720バイトのフラッシュメモリのうち、スケッチが1087009バイト(82%)を使っています。
- 最大327680バイトのRAMのうち、グローバル変数が39620バイト(12%)を使っていて、
- ローカル変数で288060バイト使うことができます。
- ボード:ESP32 Dev Module
- 効果音はJQ8400i
- モータドライバはDRV8835
- 【操作手順】
- 電源スイッチON。
- PSボタンでペアリング開始。
- 赤色インジケータランプ高速点滅。点灯でペアリング完了。
- 【走行コントロール】
- コントローラーの左スティック上下で前後進、
- 右スティックの左右でステアリングを制御。
- ステアリングを振っていくと回転軸側が減速していき(緩旋回から信地旋回)、
- 一杯に倒すと回転軸側は停止。(信地旋回)
- 左スティック中央で右ステアリングを一杯に振ると超信地旋回(速度50%)
- 【砲塔旋回】左十字キーRボタンで左側砲塔右旋回、Lボタンで左旋回。
- 右十字キー 〇ボタンで右側砲塔右旋回、□ボタンで左旋回。
- ボタンを押している間旋回、放した位置で停止。
- 純正PS3コントローラでないと、旋回が上手く出来ない。
- 【主 砲】R1ボタンで右主砲発砲、L1ボタンで左主砲発砲。
- 【機関銃】?ボタンで右機関銃発砲、DOWNボタンで左機関銃発砲、
- △ボタンで前機関銃発砲。
- */
- #include <Arduino.h> // Arduino ヘッダインクルード
- //#include "SoftwareSerial.h" // EspSoftwareSerial
- //SoftwareSerial mySerial(16, 17); // RX, TX EspSoftwareSerial
- HardwareSerial Serial_df(2); // use HardwareSerial UART2 (16pin=RX, 17pin=TX)
- #include <JQ8400_Serial.h>
- JQ8400_Serial mp3(Serial_df);
- #include <Ps3Controller.h>
- #include <ESP32Servo.h>
- Servo servo1;
- int servo1Pin = 27;
- Servo servo2;
- int servo2Pin = 14;
- int LED_1 = 23; //左主砲
- int LED_2 = 22; //右主砲
- int LED_3 = 18; //左機関銃
- int LED_4 = 19; //右機関銃
- int LED_5 = 5; //前機関銃
- int k = 0;
- int s = 0;
- int d_time = 50;
- int d_time1 = 10;
- int angle_servo1 = 80; // 左砲塔旋回
- int anglenow1 = angle_servo1 ;
- int angle_servo2 = 90; // 右砲塔旋回
- int anglenow2 = angle_servo2 ;
- 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 = 33; // A入力2/AENABLE 左モータ AIN2
- int PWMBpin = 26; // B入力2/BENABLE 右モータ BIN2
- 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 FH-1083
- servo1.attach(servo1Pin, 500, 2400); // (servo1Pin, minUs, maxUs)
- servo2.setPeriodHertz(50); // Standard 50hz servo PWMサイクル:20mS
- servo2.attach(servo2Pin, 500, 2400); // (servo1Pin, minUs, maxUs)
- //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に修正
- Serial.println("PS3 Ready");
- // Now we cam reset.
- mp3.reset();
- mp3.setVolume(25);
- 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_1, OUTPUT); //左主砲
- pinMode(LED_2, OUTPUT); //右主砲
- pinMode(LED_3, OUTPUT); //左機関銃
- pinMode(LED_4, OUTPUT); //右機関銃
- pinMode(LED_5, OUTPUT); //前機関銃
- servo1.write(angle_servo1); // 85
- delay(100);
- servo2.write(angle_servo2); // 90
- delay(100);
- mp3.playFileByIndexNumber(3); //エンジン始動
- delay(1000);
- LEDtenmetsu(LED_5); //Ready go
- }
- 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 ( abs(Ps3.event.analog_changed.button.right) && ( anglenow1 > 30 )) {
- anglenow1 -= 1;
- servo1.write(anglenow1);
- delay(d_time1);
- }
- //左側砲塔 左旋回
- if ( abs(Ps3.event.analog_changed.button.left) && ( anglenow1 < 125 )) {
- anglenow1 += 1 ;
- servo1.write(anglenow1);
- delay(d_time1);
- }
- // 右側砲塔 右旋回
- if ( abs(Ps3.event.analog_changed.button.circle) && ( anglenow2 > 45 )) {
- anglenow2 -= 1;
- servo2.write(anglenow2);
- delay(d_time1);
- }
- // 右側砲塔 左旋回
- if ( abs(Ps3.event.analog_changed.button.square) && ( anglenow2 < 145 )) {
- anglenow2 += 1 ;
- servo2.write(anglenow2);
- delay(d_time1);
- }
- if (Ps3.event.button_down.r1) { //右主砲 発砲
- digitalWrite(LED_2, HIGH); //右主砲発光
- mp3.playFileByIndexNumber(1);
- delay(300);
- digitalWrite(LED_2, LOW);
- delay(20);
- }
- if (Ps3.event.button_down.l1) { //左主砲 発砲
- digitalWrite(LED_1, HIGH); //左主砲発光
- mp3.playFileByIndexNumber(1);
- delay(300);
- digitalWrite(LED_1, LOW);
- delay(20);
- }
- if (Ps3.event.button_down.cross) { //右機関銃
- mp3.playFileByIndexNumber(10);
- delay(100);
- for ( k = 0; k < 5; k++) {
- digitalWrite(LED_4, HIGH); //発光
- delay(80);
- digitalWrite(LED_4, LOW);
- delay(120);
- }
- }
- if (Ps3.event.button_down.down) { //左機関銃
- mp3.playFileByIndexNumber(10);
- delay(100);
- for ( k = 0; k < 5; k++) {
- digitalWrite(LED_3, HIGH); //発光
- delay(80);
- digitalWrite(LED_3, LOW);
- delay(120);
- }
- }
- if (Ps3.event.button_down.triangle) { //前機関銃
- mp3.playFileByIndexNumber(10);
- delay(100);
- for ( k = 0; k < 5; k++) {
- digitalWrite(LED_5, HIGH); //発光
- delay(80);
- digitalWrite(LED_5, LOW);
- delay(120);
- }
- }
- //走行コントロール
- //前進
- 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
- ledcWrite(PWMA, D0); //(チャンネル,解像度)
- digitalWrite(AIN1, D1);
- ledcWrite(PWMB, D2); //(チャンネル,解像度)
- digitalWrite(BIN1, D3);
- }
- void LEDtenmetsu(int LED) {
- for (int i = 0; i < 2; i++) {
- digitalWrite(LED, HIGH);
- delay(500);
- digitalWrite(LED, LOW);
- delay(500);
- }
- }
【回路図】
※コメント投稿者のブログIDはブログ作成者のみに通知されます