====== Набор «Драгстер»: исходники программ для экспериментов ====== [[amp>product/dragster?utm_source=man&utm_campaign=dragster&utm_medium=wiki|{{ :dragster:dragster_title.png?nolink&700 |}}]] ==== Исходники ==== === 1 === void setup() { pinMode(LED_BUILTIN, OUTPUT); } void loop() { digitalWrite(LED_BUILTIN, HIGH); delay(1000); digitalWrite(LED_BUILTIN, LOW); delay(1000); } === 2 === void setup() { pinMode(LED_BUILTIN, OUTPUT); } void loop() { digitalWrite(LED_BUILTIN, HIGH); delay(1000); digitalWrite(LED_BUILTIN, LOW); delay(1000); } === 3 === void setup() { pinMode(10, INPUT); pinMode(LED_BUILTIN, OUTPUT); } void loop() { if (digitalRead(10) == 0) { digitalWrite(LED_BUILTIN, HIGH); } else { digitalWrite(LED_BUILTIN, LOW); } } === 4 === void setup() { pinMode(4, OUTPUT); pinMode(5, OUTPUT); pinMode(6, OUTPUT); pinMode(7, OUTPUT); digitalWrite(4, HIGH); digitalWrite(7, HIGH); } void loop() { analogWrite(5, 64); analogWrite(6, 64); delay(1000); analogWrite(5, 0); analogWrite(6, 0); delay(1000); } === 5 === #define DIR1 4 #define DIR2 7 #define EN1 5 #define EN2 6 void setup() { pinMode(DIR1, OUTPUT); pinMode(EN1, OUTPUT); pinMode(EN2, OUTPUT); pinMode(DIR2, OUTPUT); digitalWrite(DIR1, HIGH); digitalWrite(DIR2, HIGH); analogWrite(EN1, 45); analogWrite(EN2, 90); } void loop() { } === 6 === [[https://github.com/amperka/Dragster/archive/1.0.0.zip|Библиотека Dragster]] - Нажми на ссылку библиотеки — браузер скачает zip-архив. - Открой в Arduino IDE и перейди в меню Скетч Подключить библиотеку Добавить .ZIP библиотеку… - В окне выбора файла открой скачанный zip-архив и нажми Open. - Библиотека готова к использованию. #include "Dragster.h" Dragster robot; void setup() { robot.begin(); // robot.begin(SWAP_RIGHT); // robot.begin(SWAP_LEFT); // robot.begin(SWAP_BOTH); } void loop() { robot.drive(110, 50); delay(1000); robot.drive(50, 110); delay(1000); } === 7 === [[https://github.com/amperka/TroykaLedMatrix/archive/1.0.2.zip|Библиотека TroykaLedMatrix]] [[продукты:troyka-led-matrix|Подробное описание]] LED-матрицы. #include "Dragster.h" #include "TroykaLedMatrix.h" Dragster robot; TroykaLedMatrix matrix; uint8_t stop[] { 0b11111111, 0b11111111, 0b11111111, 0b11111111, 0b11111111, 0b11111111, 0b11111111, 0b11111111, }; void setup() { robot.begin(); matrix.begin(); } void loop() { matrix.clear(); robot.drive(120, 120); delay(1000); matrix.drawBitmap(stop); robot.drive(0, 0); delay(1000); } === 8 === [[https://amperka.github.io/led-matrix-editor/|Редактор изображений]] #include "Dragster.h" #include "TroykaLedMatrix.h" Dragster robot; TroykaLedMatrix matrix; const byte IMAGES[][8] = { {0x18, 0x30, 0x60, 0xff, 0xff, 0x60, 0x30, 0x18}, {0x18, 0x0c, 0x06, 0xff, 0xff, 0x06, 0x0c, 0x18} }; const int IMAGES_LEN = sizeof(IMAGES) / 8; void setup() { robot.begin(); matrix.begin(); } void loop() { matrix.drawBitmap(IMAGES[0]); robot.drive(110, 60); delay(1000); matrix.drawBitmap(IMAGES[1]); robot.drive(60, 110); delay(1000); } === 9 === #include "TroykaLedMatrix.h" TroykaLedMatrix matrix; const byte IMAGES[][8] = { {0x30, 0x78, 0xcc, 0xcc, 0xfc, 0xcc, 0xcc, 0x00}, {0xc6, 0xee, 0xfe, 0xfe, 0xd6, 0xc6, 0xc6, 0x00}, {0xfc, 0x66, 0x66, 0x7c, 0x60, 0x60, 0xf0, 0x00}, {0xfe, 0x62, 0x68, 0x78, 0x68, 0x62, 0xfe, 0x00}, {0xfc, 0x66, 0x66, 0x7c, 0x6c, 0x66, 0xe6, 0x00}, {0xe6, 0x66, 0x6c, 0x78, 0x6c, 0x66, 0xe6, 0x00}, {0x30, 0x78, 0xcc, 0xcc, 0xfc, 0xcc, 0xcc, 0x00}, {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00} }; const int IMAGES_LEN = sizeof(IMAGES) / 8; byte shift = 0; void setup() { matrix.begin(); } void loop() { delay(70); matrix.marquee(IMAGES, IMAGES_LEN, shift++); if (shift == IMAGES_LEN * 8) { shift = 0; } } === 10 === #include "TroykaLedMatrix.h" TroykaLedMatrix matrix; byte valume[8] = {0x80, 0xc0, 0xe0, 0xf0, 0xf8, 0xfc, 0xfe, 0xf}; byte diagram[8] = {0, 0, 0, 0, 0, 0, 0, 0}; float R1 = 10000; float R2 = 36000; void setup() { matrix.begin(); pinMode(A1, INPUT); } void loop() { delay(200); int adcValue = analogRead(A1); float V = adcValue * 5.0 / 1023.0; float Vbat = V * (R1 + R2) / R2; int matrixValue = (Vbat - 3.2) * 8; for (int i = 0; i < 8; i++) { if (i < matrixValue) { diagram[i] = valume[i]; } else { diagram[i] = 0x00; } } matrix.drawBitmap(diagram); } === 11 === #include "Dragster.h" #define ENC1 0 Dragster robot; void setup() { pinMode(ENC1, INPUT); robot.begin(); robot.drive(120, 0); Serial.begin(115200); } void loop() { Serial.println(digitalRead(ENC1)); delay(100); } === 12 === #include "Dragster.h" Dragster robot; int counter = 0; void leftEncoder() { counter++; } void rightEncoder() { } void setup() { robot.begin(); robot.encodersBegin(leftEncoder, rightEncoder); robot.drive(60, 0); Serial.begin(115200); } void loop() { Serial.println(counter); delay(200); } === 13 === #include "Dragster.h" Dragster robot; float left = 0; float right = 0; void leftEncoder() { left = left + 9.42; } void rightEncoder() { right = right + 9.42; } void setup() { robot.begin(); robot.encodersBegin(leftEncoder, rightEncoder); robot.drive(100, 120); Serial.begin(115200); } void loop() { Serial.print(left); Serial.print(" "); Serial.print(right); Serial.println(); delay(20); } === 14 === #include "Dragster.h" #include "TroykaLedMatrix.h" Dragster robot; TroykaLedMatrix matrix; byte diagram[8] = {0, 0, 0, 0, 0, 0, 0, 0}; int speed = 0; void handler() { speed++; } void setup() { robot.begin(); robot.encodersBegin(handler, handler); robot.drive(40, 80); matrix.begin(); } void loop() { for (int i = 0; i < 8; i++) { if (speed > i) { diagram[i] = matrix.map(8 - (i + 1), 0, 8); } else { diagram[i] = 0; } } matrix.drawBitmap(diagram); speed = 0; delay(150); } Если Драгстер слишком быстр, попробуй сравнивать с переменной i не полную скорость, а половину: … for (int i = 0; i < 8; i++) { if (speed / 2 > i) { … === 16 === [[https://github.com/amperka/Octoliner/archive/1.2.5.zip|Библиотека Octoliner]] [[products:zelo-follow-line-sensor-v1|Подробное описание]] датчика линии. #include "TroykaLedMatrix.h" #include "Octoliner.h" Octoliner octoliner; TroykaLedMatrix matrix; byte diagram[8] = {0, 0, 0, 0, 0, 0, 0, 0}; void setup() { matrix.begin(); octoliner.begin(120); } void loop() { for (int i = 0; i < 8; i++) { int analogValue = octoliner.analogRead(i); diagram[i] = matrix.map(analogValue, 0, 4095); } matrix.drawBitmap(diagram); } === 17 === #include "Dragster.h" #include "TroykaLedMatrix.h" #include "Octoliner.h" Dragster robot; TroykaLedMatrix matrix; Octoliner octoliner; byte diagram[8] = {0}; void setup() { robot.begin(); matrix.begin(); octoliner.begin(200); } void loop() { for (int i = 0; i < 8; i++) { int adcValue = octoliner.analogRead(i); diagram[i] = matrix.map(adcValue, 0, 4095); if (diagram[i] < 4) { robot.drive(0, 0); } } matrix.drawBitmap(diagram); if (robot.readButton() == 0) { delay(1000); robot.drive(255, 255); } } === 18 === #include "Dragster.h" #include "TroykaLedMatrix.h" #include "Octoliner.h" Dragster robot; TroykaLedMatrix matrix; Octoliner octoliner; byte diagram[8] = {0}; float weight[] = { -1, -0.75, -0.5, -0.25, 0.25, 0.5, 0.75, 1}; float Kp = 0.5; void setup() { robot.begin(); matrix.begin(); octoliner.begin(200); } void loop() { float error = 0; float sum = 0; float sumWeighted = 0; for (int i = 0; i < 8; i++) { int adcValue = octoliner.analogRead(i); diagram[i] = matrix.map(adcValue, 0, 4095); sum += adcValue; sumWeighted += adcValue * weight[i]; } if (sum != 0.0) { error = sumWeighted / sum; } matrix.drawBitmap(diagram); robot.driveF(0.35 - error * Kp, 0.35 + error * Kp); } === 19 === [[https://github.com/amperka/PID_dragster/archive/2.0.0.zip|Библиотека PID_dragster]] #include "Dragster.h" #include "Octoliner.h" #include "PID_dragster.h" Dragster robot; Octoliner octoliner; int lineData[8] = {0}; float speed = 0.35; float KP = 0.5; double error = 0; double output; PID regulator(&output, KP, 0, 0); void setup() { robot.begin(); octoliner.begin(200); } void loop() { for (int i = 0; i < 8; i++) { lineData[i] = octoliner.analogRead(i); } error = octoliner.mapLine(lineData); regulator.compute(error); robot.driveF(speed - output, speed + output); } === 20 === #include "Dragster.h" #include "Octoliner.h" #include "PID_dragster.h" Dragster robot; Octoliner octoliner; int lineData[8] = {0}; int threshold = 2000; float speed = 0.5; float KP = 0.6; float KD = 0.02; double error = 0; double output; PID regulator(&output, KP, 0, KD); void setup() { robot.begin(); octoliner.begin(200); } void loop() { for (int i = 0; i < 8; i++) { lineData[i] = octoliner.analogRead(i); } error = octoliner.mapLine(lineData); regulator.compute(error); robot.driveF(speed - output, speed + output); } === 21 === #include "Dragster.h" #include "Octoliner.h" #include "PID_dragster.h" Dragster robot; Octoliner octoliner; int lineData[8] = {0}; int threshold = 2000; float speed = 0.7; float KP = 0.6; float KD = 0.02; float KI = 0.0; float error = 0; double output; PID regulator(&output, KP, KI, KD); void setup() { robot.begin(); octoliner.begin(200); } void loop() { for (int i = 0; i < 8; i++) { lineData[i] = octoliner.analogRead(i); } error = octoliner.mapLine(lineData); regulator.compute(error); robot.driveF(speed - output, speed + output); }