- /* PS4BT_arduino_pro mini_tank_DRV8835_MP3_M1A2_ver05c
- Arduino pro min + ミニUSBホストシールド2.0 + PS4コントローラ
- 効果音はDFPlayer Mini
- モータドライバはDRV8835
- 効果音制御はサブシステム(arduino_pro mini_tank_MP3_sub_ver04switch)で実施
- シリアル通信データ
- エンジン始動音停止 100
- 砲撃 101
- 銃撃 102
- エンジン停止/始動 110
- ライトスイッチ 120
- 砲身center 130
- 砲身UP 131
- 砲身DOWN 132
- 砲撃時のリコイルアクション 砲身のみ (車体のリコイル動作廃止) ver03 2022/03/22
- ヘッドライト、ブレーキランプはミニUSBシールドのGPOUTピン0,1,2,3
- 【操作手順】
- SHARE+PSボタンでペアリング開始。白色インジケータランプ高速点滅。
- 戦車の電源投入。
- インジケータランプ青色点灯でペアリング完了。
- 【走行コントロール】
- コントローラーの左スティック上下で前後進、
- 右スティックの左右でステアリングを制御。
- ステアリングを振っていくと回転軸側が減速していき(緩旋回から信地旋回)、
- 左スティックを中央に戻し、右スティックを左右一杯に振ると超信地旋回。(速度60%)
- 停止時にブレーキランプ点灯 ミニUSB GPOUT- 3ピン
- 【砲身上下】 TRIANGLEボタンでUP。 SQUAREボタンでセンター。 CROSSボタンでDOWN。 ver04b
- 【砲塔旋回】 左スティック左右で砲塔旋回。離した位置で止まる。
- 【主砲】 R1ボタンで主砲発射
- 【機銃】 L1ボタンで機銃射撃
- 【ヘッドライト】RIGHTボタンを押して点灯、LEFTボタンを押して消灯。ミニUSB GPOUT- 2ピン
- 【ブレーキランプ】停車時のみ点灯。ミニUSB GPOUT- 3ピン
- 【BOモード】UPボタンを押してBOライトモード、DOWNボタンを押して通常モード。初期は通常モード。
- BOライト&BOテール=A0ピン、 BOブレーキ=A1ピン
- 【エンジン始動+アイドリング効果音】〇ボタンで発生、停止を交互に実施。R3ボタンで強制停止。
- 【エンジン始動音およびアイドリング音の強制停止】 R3ボタンで強制停止
- */
- #include <PS4BT.h>
- #include <usbhub.h>
- #ifdef dobogusinclude
- #include <spi4teensy3.h>
- #endif
- #include <SPI.h>
- USB Usb;
- BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so
- PS4BT PS4(&Btd, PAIR);
- bool printAngle, printTouch;
- uint8_t oldL2Value, oldR2Value;
- #include <USB_Host_Shield_GPIO.h> // GPOUTピンで主砲LEDを発光させるため
- MaxGPIO max;
- byte ser_data;
- #include <VarSpeedServo.h>
- VarSpeedServo myservo_2;
- int servo2 = 3; //servo2 砲塔旋回
- const int LED_5 = A0; //BOライト & BOテール
- const int LED_6 = A1; //BOブレーキ
- int ch = 0;
- int pos_y;
- int pos_x;
- int pos_ry;
- int pos_rx;
- int motor_speed;
- int steering;
- int PWMA = 5; // A入力2/AENABLE 左モータ AIN2
- int PWMB = 6; // B入力2/BENABLE 右モータ BIN2
- int AIN1 = 4; // A入力1/APHASE 左モータ AIN1
- int BIN1 = 7; // B入力1/BPHASE 右モータ BIN1
- int silent = 1;
- int state = 0; //変数stateを設定
- int state1 = 0;
- int BO = 0;
- int HL = 0 ;
- void setup() {
- Serial.begin (115200);
- #if !defined(__MIPSEL__)
- while (!Serial);
- #endif
- if (Usb.Init() == -1) {
- Serial.print(F("\r\nOSC did not start"));
- while (1); // Halt
- }
- Serial.print(F("\r\nPS4 Bluetooth Library Started"));
- max.write(3, HIGH); //ブレーキ点灯
- pinMode(PWMA, OUTPUT);
- pinMode(PWMB, OUTPUT);
- pinMode(AIN1, OUTPUT);
- pinMode(BIN1, OUTPUT);
- pinMode(LED_5, OUTPUT);
- pinMode(LED_6, OUTPUT);
- pinMode(servo2, OUTPUT); //servo 2 砲塔旋回
- myservo_2.attach(3); //servo2 砲塔旋回
- myservo_2.write(90);
- myservo_2.detach(); //centerセット時はコメントアウト
- }
- void loop() {
- Usb.Task();
- if (PS4.connected()) {
- // myDFPlayer.play(5);
- // delay(100);
- if (PS4.getButtonClick(R3)) { //エンジン始動音停止
- sendData(100);
- }
- if (PS4.getButtonClick(CIRCLE)) { //エンジン音停止
- sendData(110); //エンジン始動
- }
- //BOモード ⇔ 通常モード
- if (PS4.getButtonClick(UP)) {
- BO = 1; //BOモード
- lampchk(HL, BO);
- }
- if (PS4.getButtonClick(DOWN)) {
- BO = 0; //通常モード
- lampchk(HL, BO);
- }
- //砲身上下
- if ( PS4.getButtonClick(SQUARE)) { //CENTER
- sendData(130);
- }
- if (PS4.getButtonClick(TRIANGLE)) { // UP
- sendData(131);
- }
- if (PS4.getButtonClick(CROSS)) { //DOWN
- sendData(132);
- }
- //砲塔旋回
- pos_rx = PS4.getAnalogHat(LeftHatX);
- if ( pos_rx > 200) { //右旋回
- myservo_2.attach(servo2);
- myservo_2.write(83);
- } else if (pos_rx < 55) { //左旋回
- myservo_2.attach(servo2);
- myservo_2.write(102);
- } else { //停止
- myservo_2.attach(servo2);
- myservo_2.write(90);
- myservo_2.detach();
- }
- //砲撃 + リコイル
- if (PS4.getButtonClick(R1) ) {
- sendData(101); // 砲撃信号送信
- }
- //銃撃
- if ( PS4.getButtonClick(L1)) {
- sendData(102); // 銃撃信号送信
- }
- //ヘッドライト
- if (PS4.getButtonClick(RIGHT)) {
- HL = 1;
- lampchk(HL, BO);
- }
- if (PS4.getButtonClick(LEFT)) {
- HL = 0;
- sendData(120); // ライトスイッチ信号送信
- max.write(2, LOW); //消灯
- digitalWrite(LED_5, LOW); // BOライト消灯
- }
- //走行コントロール
- pos_y = PS4.getAnalogHat(LeftHatY);
- pos_x = PS4.getAnalogHat(RightHatX);
- //左スティックがセンター付近は停止(ブレーキ)
- if (pos_x >= 102 && pos_x <= 152 && pos_y >= 102 && pos_y <= 152) {
- motor_run(0, 0, 0, 0, 1, BO);
- }
- //前進
- if (pos_y <= 102 && pos_x >= 102 && pos_x <= 152) {
- motor_speed = map(pos_y, 102, 0, 0, 255);
- motor_run(motor_speed, 0, motor_speed, 0, 0, BO);
- }
- //後進
- else if ( pos_y >= 152 && pos_x >= 102 && pos_x <= 152) {
- motor_speed = map(pos_y, 152, 255, 0, 255) ;
- motor_run(motor_speed, 1, motor_speed, 1, 0, BO);
- }
- //前進右緩旋回、信地旋回
- else if ( pos_y <= 102 && pos_x > 152) {
- motor_speed = map(pos_y, 102, 0, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_x, 152, 255, 0, 255) / 255.00));
- motor_run(motor_speed, 0, steering, 0, 0, BO);
- }
- //前進左緩旋回、信地旋回
- //else if ( pos_y <= 102 && pos_x < 102 && pos_x >= 10) {
- else if ( pos_y <= 102 && pos_x < 102) {
- motor_speed = map(pos_y, 102, 0, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_x, 102, 0, 0, 255) / 255.00));
- motor_run(steering, 0, motor_speed, 0, 0, BO);
- }
- //後進右緩旋回、信地旋回
- //else if ( pos_y >= 152 && pos_x > 152 && pos_x <= 245) {
- else if ( pos_y >= 152 && pos_x > 152 ) {
- motor_speed = map(pos_y, 152, 255, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_x, 152, 255, 0, 255) / 255.00));
- motor_run(motor_speed, 1, steering, 1, 0, BO);
- }
- //後進左緩旋回、信地旋回
- //else if ( pos_y >= 152 && pos_x < 102 && pos_x >= 10) {
- else if ( pos_y >= 152 && pos_x < 102 ) {
- motor_speed = map(pos_y, 152, 255, 0, 255);
- steering = motor_speed * (1.00 - (map(pos_x, 102, 0, 0, 255) / 255.00));
- motor_run(steering, 1, motor_speed, 1, 0, BO);
- }
- //右超信地旋回
- else if (pos_x > 245 && pos_y >= 102 && pos_y <= 152) {
- motor_speed = 155;
- motor_run(motor_speed, 0, motor_speed, 1, 0, BO);
- }
- //左超信地旋回
- else if (pos_x < 10 && pos_y >= 102 && pos_y <= 152) {
- motor_speed = 155;
- motor_run(motor_speed, 1, motor_speed, 0, 0, BO);
- }
- else { //停止(ブレーキ)
- motor_run(0, 0, 0, 0, 1, BO);
- }
- }
- }
- void motor_run(int D0, int D1, int D2, int D3, int D4, int D5) {
- analogWrite(PWMA, D0);
- digitalWrite(AIN1, D1);
- analogWrite(PWMB, D2);
- digitalWrite(BIN1, D3);
- //digitalWrite(LED_3, D4);
- if ((D4 == 1) && (D5 == 0)) {
- max.write(3, HIGH); //ブレーキ点灯
- digitalWrite(LED_6, LOW); //BOブレーキ消灯
- }
- if ((D4 == 1) && (D5 == 1)) {
- max.write(3, LOW); //ブレーキ消灯
- digitalWrite(LED_6, HIGH); //BOブレーキ点灯
- }
- if (D4 == 0) {
- max.write(3, LOW); //ブレーキ消灯
- digitalWrite(LED_6, LOW); //BOブレーキ消灯
- }
- }
- void lampchk(int D7, int D8) {
- sendData(120); // ライトスイッチ信号送信
- if ((D7 == 1) && (D8 == 0)) {
- max.write(2, HIGH); //ヘッドライト点灯
- digitalWrite(LED_5, LOW); //BOライト消灯
- }
- if ((D7 == 1) && (D8 == 1)) {
- max.write(2, LOW); //ヘッドライト消灯
- digitalWrite(LED_5, HIGH); // BOライト点灯
- }
- }
- void sendData(byte val) {
- Serial.write('H'); // ヘッダ送信
- Serial.write(val); // データ送信
- }
【サブプログラム】
- * arduino_pro mini_M1A2_MP3_sub_ver04c
- 本サブシステムの内容
- MP3プレーヤーで効果音を発生
- エンジン始動信号受信でエンジン始動、アイドリング音発生。
- 走行制御に影響する動作をサブ側へ移動
- 主砲発砲の砲身リコイルと発光をサブ側で対応
- 機銃発行をサブ側で対応
- 砲身上下動作をサブ側で対応
- シリアル通信データ
- エンジン始動 100
- 砲撃 101
- 銃撃 102
- エンジン停止/始動 110
- ライトスイッチ 120
- 砲身center 130
- 砲身UP 131
- 砲身DOWN 132
- */
- #include <SoftwareSerial.h>
- #include <DFRobotDFPlayerMini.h>
- SoftwareSerial mySerial(A2, A3); // DFPlayer TX,RX
- DFRobotDFPlayerMini myDFPlayer;
- #include <VarSpeedServo.h>
- VarSpeedServo myservo_1;
- VarSpeedServo myservo_3;
- int servo1 = 2; //servo1 砲身上下
- int servo3 = 8; //servo3 砲身リコイル
- int servo1_pos = 90; //servo1 砲身上下
- int servo3_pos = 90; //servo3 砲身リコイル
- int servo1_sp = 20; //砲身上下スピード
- byte recv_data; // 受信データ
- int silent = 1;
- int d_time = 200;
- int LED_1 = 4; //主砲
- int LED_2 = 5; //機銃
- void trancelate() //
- {
- switch (recv_data) {
- case 100: Serial.println("100"); eng_s(); break; // エンジン始動音停止
- case 101: Serial.println("101"); fire(); break; //砲撃
- case 102: Serial.println("102"); gun(); break; //銃撃
- case 110: Serial.println("110"); eng_e_s(); break; //エンジン停止/始動
- case 120: Serial.println("120"); light_sw(); break; //ライトスイッチ
- case 130: Serial.println("130"); barrel_c(); break; //砲身CENTER
- case 131: Serial.println("131"); barrel_u(); break; //砲身UP
- case 132: Serial.println("132"); barrel_d(); break; //砲身DOWN
- default: //どのcaseにも合致しないとき
- Serial.println(" other button ");
- } // End Case
- delay(100);
- } //END translate
- void eng_s() { //100 エンジン始動音停止
- myDFPlayer.disableLoopAll(); //stop loop all mp3 files.
- silent = 1;
- }
- void fire() { //101 砲撃
- PLAY_MP3(26); //砲撃音
- digitalWrite(LED_1, HIGH); //主砲発光
- myservo_3.attach(servo3);
- myservo_3.write(servo3_pos - 70, 255); //砲身リコイル
- delay(100);
- delay(60);
- digitalWrite(LED_1, LOW); //主砲消灯
- delay(80);
- myservo_3.write(servo3_pos, 20, true);
- myservo_3.detach();
- }
- void gun() { //102 銃撃
- PLAY_MP3(24);
- for ( int i = 0; i < 7 ; i++) {
- digitalWrite(LED_2, HIGH); //機銃発光
- delay(80);
- digitalWrite(LED_2, LOW); //機銃消灯
- delay(120);
- }
- }
- void eng_e_s() { //110 エンジン停止/始動
- silent = 1 - silent;
- }
- void light_sw() { //120 ライトスイッチ
- PLAY_MP3(27);
- }
- void barrel_c() { //130 砲身center
- myservo_1.attach(servo1);
- myservo_1.write(servo1_pos, servo1_sp, true);
- myservo_1.detach();
- }
- void barrel_u() { //131 砲身up
- myservo_1.attach(servo1);
- myservo_1.write(servo1_pos - 60, servo1_sp, true);
- myservo_1.detach();
- }
- void barrel_d() { //132 砲身down
- myservo_1.attach(servo1);
- myservo_1.write(servo1_pos + 30, servo1_sp, true);
- myservo_1.detach();
- }
- void setup() {
- Serial.begin (115200);
- mySerial.begin (9600);
- myDFPlayer.begin(mySerial);
- delay(100); //設定待ち時間は仮置き
- myDFPlayer.volume(25); //Set volume value (0~30)
- myDFPlayer.play(28); //エンジン始動
- delay(1000);
- pinMode(LED_1, OUTPUT); //主砲
- pinMode(LED_2, OUTPUT); //機銃
- myservo_1.attach(servo1);
- myservo_1.write(servo1_pos, 255, true);
- myservo_1.detach();
- myservo_3.attach(servo3);
- myservo_3.write(servo3_pos, 255, true);
- myservo_3.detach();
- }
- void loop() {
- Serial.println("*");
- if ( Serial.available() >= 2 ) {
- if ( Serial.read() == 'H' ) {
- recv_data = Serial.read() ;
- trancelate();
- }
- }
- if (silent == 1) {
- myDFPlayer.disableLoop(); //アイドリング停止
- } else if ( (silent == 0) && (recv_data == 110)) { //エンジン始動
- myDFPlayer.play(28); //エンジン始動
- delay(2000);
- myDFPlayer.loop(5); //Loop 5th mp3 アイドリング
- delay(d_time);
- } else {
- myDFPlayer.loop(5); //Loop 5th mp3 アイドリング
- delay(d_time);
- }
- recv_data = 0;
- }
- void PLAY_MP3(int LT) {
- recv_data = 0;
- myDFPlayer.play(LT);
- //delay(100);
- }