2018-10-30
出力ピン不足で行き詰っていたら、ネットでUSBボスとシールドのGPIOが利用できることを知った。
早速、デジタル8個のデジタル出力を利用する。
前作に対して、Arduinoの3ピンはサーボ用に戻し、ヘッドライト、ストップランプ、砲撃、銃撃の4個のLEDを操作します。
因みに、このGPIOは3.3V出力なので注意が必要です。
Arduino PS3 Bluetooth controlled tank ver.3
【変更後のスケッチ】
/*
PS3BT_arduino_tank_2dcmotor_TB6612_FIRE_A
モータドライバはTB6612
3ピンでサーボモータを動かす Ver.2
砲撃時のリコイルアクション+LED点灯、銃撃時のLED点滅(5回)の機能を追加
出力8本のGPIOを使用し、LED点灯をさせる
PS3BT_arduino_tank_2dcmotor_TB6612_FIRE_A
モータドライバはTB6612
3ピンでサーボモータを動かす Ver.2
砲撃時のリコイルアクション+LED点灯、銃撃時のLED点滅(5回)の機能を追加
出力8本のGPIOを使用し、LED点灯をさせる
*/
#include
#include
#ifdef dobogusinclude
#include
#endif
#include // needed by Arduino IDE
#include
MaxGPIO max;
#include
#include
#ifdef dobogusinclude
#include
#endif
#include // needed by Arduino IDE
#include
MaxGPIO max;
#include
Servo myservo;
int servo_pos = 90;
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; //超高速
int servo_pos = 90;
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アドレスも格納されます
// これはスケッチを実行するときにドングルから取得できます
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);
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);
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"));
}
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);
Usb.Task();
if (PS3.PS3Connected) {
//スティックの中央は127だけどピタリと止まらないので+-10ほど余裕を持たせる。
//左スティック上下の値(最上部0、中央127、最下部255)を読み込む
pos_y = PS3.getAnalogHat(LeftHatY);
pos_x = PS3.getAnalogHat(LeftHatX);
//砲撃
//リコイル
if (PS3.getButtonClick(R1) ) {
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);
delay(70);
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(95);
}
//リコイル
if (PS3.getButtonClick(R1) ) {
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);
delay(70);
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(95);
}
//サーボ UP/DOWN
if (PS3.getButtonClick(DOWN) ||
PS3.getAnalogHat(RightHatY) > 137 ||
PS3.getAnalogHat(RightHatY)
servo_pos = (int)( ( (float)PS3.getAnalogHat(RightHatY) / 255.0f ) * 180.0f);
myservo.write(servo_pos);
delay(20);
}
if (PS3.getButtonClick(UP)) {
myservo.write(0);
delay(20);
}
if (PS3.getButtonClick(DOWN)) {
myservo.write(255);
delay(20);
}
//銃撃
if ( PS3.getButtonClick(L1)) {
for ( int i = 0; i < 5 ; i++) {</span>
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(L1)) {
for ( int i = 0; i < 5 ; i++) {</span>
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(RIGHT)) {
max.write(7, HIGH);
}
if (PS3.getButtonClick(LEFT)) {
max.write(7, LOW);
}
max.write(7, LOW);
}
//左スティックがセンター付近は停止
if (pos_x >= 117 && pos_x <= 137 && pos_y >= 117 && pos_y <= 137) {
analogWrite(PWMA, 0);
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, LOW);
analogWrite(PWMA, 0);
digitalWrite(BIN1, LOW);
digitalWrite(BIN2, LOW);
max.write(2, HIGH);
}
//前進
else if (pos_y < 117 && pos_x > 117 && pos_x
//左スティック中央(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 < 117 && pos_x > 117 && pos_x
//左スティック中央(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
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 > 137 && pos_x > 117 && pos_x
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 > 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
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
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 > 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
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 > 137 && pos_x
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 > 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
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, HIGH);
analogWrite(PWMA, motor_sp1);
digitalWrite(BIN1, HIGH);
digitalWrite(BIN2, LOW);
analogWrite(PWMB, motor_sp1);
max.write(2, LOW);
}
}
}
else if ( pos_y > 117 && pos_y
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, HIGH);
analogWrite(PWMA, motor_sp1);
digitalWrite(BIN1, HIGH);
digitalWrite(BIN2, LOW);
analogWrite(PWMB, motor_sp1);
max.write(2, LOW);
}
}
}
※コメント投稿者のブログIDはブログ作成者のみに通知されます