В данной конструкции используется беспроводной джойстик от PlayStation-2.
Сборка робота:Фотоинструкция по сборке
Принципиальная схема робота:
#include < PS2X_lib.h> // пины к которым подключен PS2 джойстик: #define PS2_DAT 7 //data #define PS2_CMD 6 //command #define PS2_SEL 5 //attention #define PS2_CLK 4 //clock // выбираем режимы PS2 контроллера: #define pressures true // pressures = аналоговое считывание нажатия кнопок #define rumble true // rumble = вибромоторы // пины к которым подключен драйвер моторов: #define motorLF 9 //L-Forward #define motorLB 3 //L-Back #define motorRF 10 //R-Forward #define motorRB 11 //R-Back PS2X ps2x; // создание класса для PS2 контроллера int x,x1, y; int Weight_Forward, Weight_Back, Weight_Left, Weight_Right,Weight_Left1, Weight_Right1 ; //Веса для езды int consX = 127; //значения джосттика в среднем положении int consY = 127; void setup() { delay(300); //добавляем паузу, чтобы дать беспроводному ps2 модулю время для включения ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT, pressures, rumble); pinMode(motorLF, OUTPUT); pinMode(motorLB, OUTPUT); pinMode(motorRF, OUTPUT); pinMode(motorRB, OUTPUT); } void loop() { ps2x.read_gamepad(); //считывание данных с контроллера y = ps2x.Analog(PSS_LY); x = ps2x.Analog(PSS_RX); x1 = ps2x.Analog(PSS_LX); analogWrite(motorLF, 0); analogWrite(motorLB, 0); analogWrite(motorRF, 0); analogWrite(motorRB, 0); //--------------------------------------------------------------- if ((y < consY) && (consY - y > 3)) { Weight_Forward = map(y, 127, 0, 0, 255); } else { Weight_Forward = 0; } if ((y > consY) && (y - consY > 3)) { Weight_Back = map(y, 127, 255, 0, 255); //преобразование значений геймпада в вес } else { Weight_Back = 0; } if ((x < consX) && (consX - x > 3)) { Weight_Left = map(x, 127, 0, 0, 255); } else { Weight_Left = 0; } if ((x > consX) && (x - consX > 3)) { Weight_Right = map(x, 127, 255, 0, 255); } else { Weight_Right = 0; } if ((x1 < consX) && (consX - x1 > 3)) { Weight_Left1 = map(x1, 127, 0, 0, 255); } else { Weight_Left1 = 0; } if ((x1 > consX) && (x1 - consX > 3)) { Weight_Right1 = map(x1, 127, 255, 0, 255); } else { Weight_Right1 = 0; } //----------------------------------------------------------------- if (Weight_Forward - (Weight_Left / 1.5) > 0) { analogWrite(motorLF, Weight_Forward - (Weight_Left / 1.5)); } //----------------------------------------------------------------- if ( Weight_Back - (Weight_Right / 1.5) > 0) { analogWrite(motorLB, Weight_Back - (Weight_Right / 1.5)); } //----------------------------------------------------------------- //распределение весов на моторы //----------------------------------------------------------------- if (Weight_Forward - (Weight_Right / 1.5) > 0) { analogWrite(motorRF, Weight_Forward - (Weight_Right / 1.5)); } //----------------------------------------------------------------- if (Weight_Back - (Weight_Left / 2) > 1.5) { analogWrite(motorRB, Weight_Back - (Weight_Left / 1.5)); } //----------------------------------------------------------------- if (Weight_Forward == 0 && Weight_Back == 0) { if (Weight_Left > 0) { analogWrite(motorRF, Weight_Left); analogWrite(motorLB, Weight_Left); //разворот на месте } if (Weight_Right > 0) { analogWrite(motorLF, Weight_Right); analogWrite(motorRB, Weight_Right); } } if (Weight_Left1 > 0) { analogWrite(motorRF, Weight_Left1); //разворот на месте } if (Weight_Right1 > 0) { analogWrite(motorLF, Weight_Right1); } Serial.println(" "); delay(10); }