2018-10-27
モータドライバーを従来よく使っていたTB6612に変えます。
こちらの方が電圧降下が少なく、より低い電圧で扱えます。
実装はArduino用ユニバーサル基板を使い、積み重ねます。
入力は3.7V350mAHのLipoバッテリで、100均のモバイルバッテリの中身の昇圧コンバータで5Vを作ります。
モータドライバーを従来よく使っていたTB6612に変えます。
こちらの方が電圧降下が少なく、より低い電圧で扱えます。
実装はArduino用ユニバーサル基板を使い、積み重ねます。
入力は3.7V350mAHのLipoバッテリで、100均のモバイルバッテリの中身の昇圧コンバータで5Vを作ります。
モータドライブシールドを止めたので、スケッチを書き換えます。
特にUSBホストシールドが9ピンと10ピンを使っているので、競合しない様に他のピンに振り替えます。
この競合の事は知らなかったのですが、基板組立後の動作確認時に誤動作を繰り返すことから判りました。
特にUSBホストシールドが9ピンと10ピンを使っているので、競合しない様に他のピンに振り替えます。
この競合の事は知らなかったのですが、基板組立後の動作確認時に誤動作を繰り返すことから判りました。
【変更後のスケッチ】
// PS3BT_arduino_tank_2dcmotor_TB6612
// 空きデジタルPIN2でLEDを点灯/消灯
//モータドライバはTB6612
#include <PS3BT.h>
#include <usbhub.h>
#ifdef dobogusinclude
#include <spi4teensy3.h>
#endif
// 空きデジタルPIN2でLEDを点灯/消灯
//モータドライバはTB6612
#include <PS3BT.h>
#include <usbhub.h>
#ifdef dobogusinclude
#include <spi4teensy3.h>
#endif
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アドレスも格納されます
// これはスケッチを実行するときにドングルから取得できます
int pos_y;
int pos_x;
int PWMA = 5; // ← 11 Aモータ PWM 左側モータ
int AIN1 = 4; // ← 9 Aモータ IN1 ( 9ピンはUSBホストシールド使用
int AIN2 = 3; // ← 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 = 0; //超低速
int PWMA = 5; // ← 11 Aモータ PWM 左側モータ
int AIN1 = 4; // ← 9 Aモータ IN1 ( 9ピンはUSBホストシールド使用
int AIN2 = 3; // ← 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 = 0; //超低速
const int LED = 2;
int btn;
int i ;
int btn;
int i ;
void setup() {
Usb.Init();
Serial.begin(115200);
while (!Serial); // シリアルポートが接続するのを待つ
if (Usb.Init() == -1) {
Serial.print(F("\r\nOSC did not start"));
while (1); //halt
}
Serial.print(F("\r\nPS3 Bluetooth Library Started"));
pinMode(PWMA, OUTPUT);
pinMode(AIN1, OUTPUT);
pinMode(AIN2, OUTPUT);
pinMode(BIN1, OUTPUT);
pinMode(BIN2, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(LED, OUTPUT);
// turn on servo
//servo0.attach(9);
//servo1.attach(10);
}
Usb.Init();
Serial.begin(115200);
while (!Serial); // シリアルポートが接続するのを待つ
if (Usb.Init() == -1) {
Serial.print(F("\r\nOSC did not start"));
while (1); //halt
}
Serial.print(F("\r\nPS3 Bluetooth Library Started"));
pinMode(PWMA, OUTPUT);
pinMode(AIN1, OUTPUT);
pinMode(AIN2, OUTPUT);
pinMode(BIN1, OUTPUT);
pinMode(BIN2, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(LED, OUTPUT);
// turn on servo
//servo0.attach(9);
//servo1.attach(10);
}
void loop() {
Usb.Task();
if (PS3.PS3Connected) {
//スティックの中央は127だけどピタリと止まらないので+-10ほど余裕を持たせる。
//左スティック上下の値(最上部0、中央127、最下部255)を読み込む
pos_y = PS3.getAnalogHat(LeftHatY);
pos_x = PS3.getAnalogHat(LeftHatX);
pos_rx = PS3.getAnalogHat(RightHatX);
Usb.Task();
if (PS3.PS3Connected) {
//スティックの中央は127だけどピタリと止まらないので+-10ほど余裕を持たせる。
//左スティック上下の値(最上部0、中央127、最下部255)を読み込む
pos_y = PS3.getAnalogHat(LeftHatY);
pos_x = PS3.getAnalogHat(LeftHatX);
pos_rx = PS3.getAnalogHat(RightHatX);
//LED点灯
if (PS3.getButtonClick(UP)) {
digitalWrite(LED, HIGH);
}
//LED消灯
if (PS3.getButtonClick(DOWN)) {
digitalWrite(LED, LOW);
}
//サーボUP
// if (PS3.getButtonClick(TRIANGLE)) {
// servo0.write(168);
// delay(20);
// }
if (PS3.getButtonClick(UP)) {
digitalWrite(LED, HIGH);
}
//LED消灯
if (PS3.getButtonClick(DOWN)) {
digitalWrite(LED, LOW);
}
//サーボUP
// if (PS3.getButtonClick(TRIANGLE)) {
// servo0.write(168);
// delay(20);
// }
//サーボDOWN
// if (PS3.getButtonClick(CROSS)) {
// servo0.write(12);
// delay(20);
// }
// if (PS3.getButtonClick(CROSS)) {
// servo0.write(12);
// delay(20);
// }
//サーボ右回転
// if (pos_rx > 137) {
// servo1.write(168);
// delay(20);
// }
// if (pos_rx > 137) {
// servo1.write(168);
// delay(20);
// }
//サーボ左回転
// if (pos_rx < 117 ) {
// servo1.write(12);
// delay(20);
// }
// if (pos_rx < 117 ) {
// servo1.write(12);
// delay(20);
// }
//左スティックがセンター付近は停止
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);
}
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);
}
//前進
else if (pos_y < 117 && pos_x > 117 && pos_x < 137) {
//左スティック中央(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);
}
else if (pos_y < 117 && pos_x > 117 && pos_x < 137) {
//左スティック中央(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);
}
//後進
else if ( pos_y > 137 && pos_x > 117 && 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, HIGH);
analogWrite(PWMB, motor_speed);
}
else if ( pos_y > 137 && pos_x > 117 && 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, HIGH);
analogWrite(PWMB, motor_speed);
}
//前進右旋回
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);
}
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);
}
//前進左旋回
else if ( pos_y < 117 && pos_x < 117) {
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);
}
else if ( pos_y < 117 && pos_x < 117) {
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);
}
//後進右旋回
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);
}
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);
}
//後進左旋回
else if ( pos_y > 137 && pos_x < 117) {
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);
}
else if ( pos_y > 137 && pos_x < 117) {
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);
}
//右超信地旋回
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);
}
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);
}
//左超信地旋回
else if ( pos_y > 117 && pos_y < 137 && pos_x < 117) {
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, HIGH);
analogWrite(PWMA, motor_sp1);
digitalWrite(BIN1, HIGH);
digitalWrite(BIN2, LOW);
analogWrite(PWMB, motor_sp1);
}
}
}
else if ( pos_y > 117 && pos_y < 137 && pos_x < 117) {
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, HIGH);
analogWrite(PWMA, motor_sp1);
digitalWrite(BIN1, HIGH);
digitalWrite(BIN2, LOW);
analogWrite(PWMB, motor_sp1);
}
}
}
※コメント投稿者のブログIDはブログ作成者のみに通知されます