/*
Управление двумя коллекторными двигателями постоянного тока через MOSFET, Arduino Nano и FLYSKY приемник.
использую левый стик пульта -это каналы 3 и 4 приемника.
*/
byte m1p1t1V7 = 7; // мотор 1, пин мотора 1, транзистор 1, питание плюс, пин ардуино 7 соответственно.m1p1t1Vpvm10
byte m1p2t2Gpvm3 = 3;//Мотор1, пин мотора2, транзистор2, питание минус, шим, пин ардуино 3.
byte m1p2t3V8 = 8;
byte m1p1t4Gpvm9 = 9;
byte m2p1t5V12 = 12;
byte m2p2t6Gpvm10 = 10;
byte m2p2t7V13 = 13;
byte m2p1t8Gpvm11 = 11;
byte channelFS_3 = A1; //третий канал приемника FS и пин A1(15) ардуино.
byte channelFS_4 = A2;
void setup() {
TCCR1A = 0b00000001; // 8bit Пины D9 и D10 - 31.4 кГц
TCCR1B = 0b00000001; // x1 phase correct
TCCR2B = 0b00000001; // Пины D3 и D11 - 31.4 кГц
TCCR2A = 0b00000001; // x1 phase correct
pinMode(m1p1t1V7, OUTPUT);//по умолчанию (..., OUTPUT) это(...,LOW).
pinMode(m1p2t2Gpvm3, OUTPUT);//Первый мотор(m1),второй пин мотора (p2), второй транзистор(t2), питание зимля(G),шим(pvm), третий пин ардуино(3).
pinMode(m1p2t3V8, OUTPUT);//Первый мотор(m1),второй пин мотора (p2), третий транзистор(t3), питание плюс(V), восьмой пина ардуино (8).
pinMode(m1p1t4Gpvm9, OUTPUT);
pinMode(m2p1t5V12, OUTPUT);
pinMode(m2p2t6Gpvm10, OUTPUT);
pinMode(m2p2t7V13, OUTPUT);
pinMode(m2p1t8Gpvm11, OUTPUT);
// Serial.begin(9600);//последовательный порт
}
void loop() {
/*****************************************Приемная часть кода***********************************/
int pwm1 = 0;
int pwm2 = 0;
int FS_3 = pulseIn(channelFS_3, HIGH);
int FS_4 = pulseIn(channelFS_4, HIGH);
if (FS_3 != 0 || FS_4 != 0) {
FS_3 = FS_3 - 1480;//диапазон приемника примерно 900-1970(микросекунды).
FS_4 = FS_4 - 1480;//приводим значение среднего положениея стиков к нолю.
}
int v1 = FS_3 + FS_4;//преобразуем данные приемника с двух стиков(3,4) пульта в данные (v) для двигателя (1).
int v2 = FS_3 - FS_4;
//Serial.print("FS_3 ");
//Serial.print(FS_3);
//Serial.print(" FS_4 ");
//Serial.print(FS_4);
//Serial.print(" v1 ");
//Serial.print(v1);
//Serial.print(" v2 ");
//Serial.print(v2);
/****************************Драйверная часть кода**********************************************/
if (v1 >= 20) { //На первый пин (p1) первого дигателя (м1) подаем плюс(V).
pwm1 = map(v1, 20, 500, 150, 255);//маштабируем диапазон датчиков в диапазон шим. ((НАСТРОИТЬ ПОРОГИ ШИМ ПУСКА И МАКСИМАЛЬНЫЙ ТОК НА ВЫХОДЕ !!!!))
digitalWrite(m1p2t3V8, LOW);//Первым закрываем t3 он же плюс питания V.
digitalWrite(m1p1t4Gpvm9, LOW);//Вторым закрываем четвертый транзистор GND(t4). Первый пин первого двигателя.
delay(1);//время на закрытие мосфетов при смене полярности.
analogWrite(m1p2t2Gpvm3, pwm1);//Подаем шим на второй транзистор(t2), включенный параллельно третьему транзистору (t3). Второй пин (p2) первого двигателя(m1). Шим открывает GND.
digitalWrite(m1p1t1V7, HIGH);//Открываем первый пин первого двигателя через первый транзистор. плюс питания (V).
}
if (v1 <= -20) { //На второй пин (p2) первого дигателя (м1) подаем плюс(V).
pwm1 = map(v1, -20, -500, 150, 255);
digitalWrite(m1p1t1V7, LOW); //закрываем первый транзистор (t1) включенный параллельно четвертому транзистору (t4). Первый пин первого двигателя.
digitalWrite(m1p2t2Gpvm3, LOW); //Отключаем землю от второго пина первого двигателя.
delay(1);
analogWrite(m1p1t4Gpvm9, pwm1); //открываем "-" шим для второго пина двигателя.
digitalWrite(m1p2t3V8, HIGH); //Открываем "+" на первом пине двигателя.
}
if (v1 > -20 && v1 < 20) { //Двигатель 1 на месте.
digitalWrite(m1p1t1V7, LOW);
digitalWrite(m1p2t2Gpvm3, LOW);
digitalWrite(m1p2t3V8, LOW);
digitalWrite(m1p1t4Gpvm9, LOW);
}
if (v2 >= 20) { //На первый пин (p1) второго дигателя (м2) подаем плюс(V).
pwm2 = map(v2, 20, 500, 150, 255);
digitalWrite(m2p2t7V13, LOW);
digitalWrite(m2p1t8Gpvm11, LOW);
delay(1);
analogWrite(m2p2t6Gpvm10, pwm2);
digitalWrite(m2p1t5V12, HIGH);
}
if (v2 <= -20) { //На второй пин (p2) второго дигателя (м2) подаем плюс(V).
pwm2 = map(v2, -20, -500, 150, 255);
digitalWrite(m2p1t5V12, LOW);
digitalWrite(m2p2t6Gpvm10, LOW);
delay(1);
analogWrite(m2p1t8Gpvm11, pwm2);
digitalWrite(m2p2t7V13, HIGH);
}
if (v2 > -20 && v2 < 20) { //Двигатель 2 на месте.
digitalWrite(m2p1t5V12, LOW);
digitalWrite(m2p2t6Gpvm10, LOW);
digitalWrite(m2p2t7V13, LOW);
digitalWrite(m2p1t8Gpvm11, LOW);
}
//Serial.print(" pwm1 ");
//Serial.print(pwm1);
//Serial.print(" pwm2 ");
//Serial.println(pwm2);
}