├── .gitattributes
├── README.md
├── firmware
├── mecanum_ps2
│ └── mecanum_ps2.ino
└── mecanum_ps2_opto
│ ├── encoder.h
│ └── mecanum_ps2_opto.ino
├── libraries
├── AccelMotor
│ ├── AccelMotor.cpp
│ ├── AccelMotor.h
│ ├── docs
│ │ └── jga25.jpg
│ ├── keywords.txt
│ └── library.properties
├── GyverMotor
│ ├── LICENSE
│ ├── README.md
│ ├── examples
│ │ ├── GyverMotor
│ │ │ ├── motor_control_10bit
│ │ │ │ └── motor_control_10bit.ino
│ │ │ ├── motor_control_31kHz
│ │ │ │ └── motor_control_31kHz.ino
│ │ │ ├── motor_demo
│ │ │ │ └── motor_demo.ino
│ │ │ ├── multi_motor
│ │ │ │ └── multi_motor.ino
│ │ │ ├── multi_motor_tank
│ │ │ │ └── multi_motor_tank.ino
│ │ │ └── smooth_control
│ │ │ │ └── smooth_control.ino
│ │ └── GyverMotor2
│ │ │ ├── demo
│ │ │ └── demo.ino
│ │ │ ├── potControl
│ │ │ └── potControl.ino
│ │ │ └── serialControl
│ │ │ └── serialControl.ino
│ ├── keywords.txt
│ ├── library.properties
│ └── src
│ │ ├── GyverMotor.cpp
│ │ ├── GyverMotor.h
│ │ └── GyverMotor2.h
└── PS2X_lib
│ ├── PS2X_lib.cpp
│ ├── PS2X_lib.h
│ ├── examples
│ ├── PS2XMouse
│ │ └── PS2XMouse.ino
│ └── PS2X_Example
│ │ └── PS2X_Example.ino
│ └── keywords.txt
└── schemes
├── scheme.jpg
└── scheme2.jpg
/.gitattributes:
--------------------------------------------------------------------------------
1 | # Auto detect text files and perform LF normalization
2 | * text=auto
3 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | 
2 |
3 | # Платформа на всенаправленных колёсах
4 | * [Описание проекта](#chapter-0)
5 | * [Как скачать и прошить](#chapter-2)
6 | * [FAQ](#chapter-3)
7 | * [Полезная информация](#chapter-4)
8 | [](https://www.youtube.com/channel/UCgtAOyEQdAyjvm9ATCi_Aig?sub_confirmation=1)
9 |
10 |
11 | ## Описание проекта
12 | Платформа на всенаправленных колёсах под управлением Arduino.
13 |
14 | ### Железо
15 | - Проект собран на базе микроконтроллера Arduino Nano
16 | - Джойстик от PS2 с приемником
17 | - Всенаправленные колеса с платформой
18 | - Драйверы для моторов
19 | - Литиевые батарейки
20 | - Пара конденденсаторов
21 | (см. схему)
22 |
23 |
24 | ## Как скачать и прошить
25 | * [Первые шаги с Arduino](http://alexgyver.ru/arduino-first/) - ультра подробная статья по началу работы с Ардуино, ознакомиться первым делом!
26 | * Скачать архив с проектом
27 | > На главной странице проекта (где ты читаешь этот текст) вверху справа зелёная кнопка **Clone or download**, вот её жми, там будет **Download ZIP**
28 | * Установить библиотеки в
29 | `C:\Program Files (x86)\Arduino\libraries\` (Windows x64)
30 | `C:\Program Files\Arduino\libraries\` (Windows x86)
31 | * **Подключить внешнее питание 5 Вольт**
32 | * Подключить плату к компьютеру
33 | * Файл/Настройки, вставить ссылку http://arduino.esp8266.com/stable/package_esp8266com_index.json в в текст-бокс для дополнительных ссылок для менеджера плат
34 | * Открыть Инструменты/Плата/Менеджер плат…, найти esp8266 by ESP8266 Community, установить версию 2.5.0
35 | * Открыть Инструменты, настроить Плату, Порт и другие параметры как на скриншоте
36 | * Загрузить прошивку
37 |
38 |
39 |
40 |
41 | ## FAQ
42 | ### Основные вопросы
43 | В: Как скачать с этого грёбаного сайта?
44 | О: На главной странице проекта (где ты читаешь этот текст) вверху справа зелёная кнопка **Clone or download**, вот её жми, там будет **Download ZIP**
45 |
46 | В: Скачался какой то файл .zip, куда его теперь?
47 | О: Это архив. Можно открыть стандартными средствами Windows, но думаю у всех на компьютере установлен WinRAR, архив нужно правой кнопкой и извлечь.
48 |
49 | В: Я совсем новичок! Что мне делать с Ардуиной, где взять все программы?
50 | О: Читай и смотри видос http://alexgyver.ru/arduino-first/
51 |
52 | В: Вылетает ошибка загрузки / компиляции!
53 | О: Читай тут: https://alexgyver.ru/arduino-first/#step-5
54 |
55 | В: Сколько стоит?
56 | О: Ничего не продаю.
57 |
58 |
59 | ## Полезная информация
60 | * [Мой сайт](http://alexgyver.ru/)
61 | * [Основной YouTube канал](https://www.youtube.com/channel/UCgtAOyEQdAyjvm9ATCi_Aig?sub_confirmation=1)
62 | * [YouTube канал про Arduino](https://www.youtube.com/channel/UC4axiS76D784-ofoTdo5zOA?sub_confirmation=1)
63 | * [Мои видеоуроки по пайке](https://www.youtube.com/playlist?list=PLOT_HeyBraBuMIwfSYu7kCKXxQGsUKcqR)
64 | * [Мои видеоуроки по Arduino](http://alexgyver.ru/arduino_lessons/)
65 |
66 |
67 |
--------------------------------------------------------------------------------
/firmware/mecanum_ps2/mecanum_ps2.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Скетч к проекту "Телега на всенаправленных колёсах"
3 | - Страница проекта (схемы, описания): https://alexgyver.ru/mecanumbot
4 | - Исходники на GitHub: https://github.com/AlexGyver/MecanumBot/
5 | Проблемы с загрузкой? Читай гайд для новичков: https://alexgyver.ru/arduino-first/
6 | Нравится, как написан код? Поддержи автора! https://alexgyver.ru/support_alex/
7 | AlexGyver, AlexGyver Technologies, 2020
8 | https://www.youtube.com/c/alexgyvershow
9 | https://github.com/AlexGyver
10 | https://AlexGyver.ru/
11 | alex@alexgyver.ru
12 | */
13 |
14 | #define MAX_SPEED 170 // максимальная скорость моторов (0-255)
15 |
16 | #define MOTOR_TEST 0 // тест моторов
17 | // при запуске крутятся ВПЕРЁД по очереди:
18 | // FL - передний левый
19 | // FR - передний правый
20 | // BL - задний левый
21 | // BR - задний правый
22 |
23 | // пины драйверов (_B должен быть ШИМ)
24 | #define MOTOR1_A 2
25 | #define MOTOR1_B 3 // ШИМ!
26 | #define MOTOR2_A 4
27 | #define MOTOR2_B 5 // ШИМ!
28 | #define MOTOR3_A 7
29 | #define MOTOR3_B 6 // ШИМ!
30 | #define MOTOR4_A 8
31 | #define MOTOR4_B 9 // ШИМ!
32 |
33 | #include
34 | // тут можно поменять моторы местами
35 | GMotor motorBL(DRIVER2WIRE, MOTOR1_A, MOTOR1_B, HIGH);
36 | GMotor motorFL(DRIVER2WIRE, MOTOR2_A, MOTOR2_B, HIGH);
37 | GMotor motorFR(DRIVER2WIRE, MOTOR3_A, MOTOR3_B, HIGH);
38 | GMotor motorBR(DRIVER2WIRE, MOTOR4_A, MOTOR4_B, HIGH);
39 |
40 | // пины ресивера ps2
41 | #define PS2_DAT A0
42 | #define PS2_CMD A1
43 | #define PS2_SEL A2
44 | #define PS2_CLK A3
45 |
46 | #include
47 | PS2X ps2x;
48 |
49 | void setup() {
50 | Serial.begin(9600);
51 | // чуть подразгоним ШИМ https://alexgyver.ru/lessons/pwm-overclock/
52 | // Пины D3 и D11 - 980 Гц
53 | TCCR2B = 0b00000100; // x64
54 | TCCR2A = 0b00000011; // fast pwm
55 |
56 | // Пины D9 и D10 - 976 Гц
57 | TCCR1A = 0b00000001; // 8bit
58 | TCCR1B = 0b00001011; // x64 fast pwm
59 |
60 | // тест моторов
61 | #if (MOTOR_TEST == 1)
62 | Serial.println("front left");
63 | motorFL.run(FORWARD, 100);
64 | delay(3000);
65 | motorFL.run(STOP);
66 | delay(1000);
67 | Serial.println("front right");
68 | motorFR.run(FORWARD, 100);
69 | delay(3000);
70 | motorFR.run(STOP);
71 | delay(1000);
72 | Serial.println("back left");
73 | motorBL.run(FORWARD, 100);
74 | delay(3000);
75 | motorBL.run(STOP);
76 | delay(1000);
77 | Serial.println("back right");
78 | motorBR.run(FORWARD, 100);
79 | delay(3000);
80 | motorBR.run(STOP);
81 | #endif
82 | // минимальный сигнал на мотор
83 | motorFR.setMinDuty(30);
84 | motorBR.setMinDuty(30);
85 | motorFL.setMinDuty(30);
86 | motorBL.setMinDuty(30);
87 |
88 | // режим мотора в АВТО
89 | motorFR.setMode(AUTO);
90 | motorBR.setMode(AUTO);
91 | motorFL.setMode(AUTO);
92 | motorBL.setMode(AUTO);
93 |
94 | // скорость плавности
95 | motorFR.setSmoothSpeed(60);
96 | motorBR.setSmoothSpeed(60);
97 | motorFL.setSmoothSpeed(60);
98 | motorBL.setSmoothSpeed(60);
99 |
100 | delay(1000); // ждём запуска контроллера
101 | ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT, false, false);
102 | }
103 |
104 | void loop() {
105 | //DualShock Controller
106 | bool success = ps2x.read_gamepad(false, 0); // читаем
107 | ps2x.reconfig_gamepad(); // костыль https://stackoverflow.com/questions/46493222/why-arduino-needs-to-be-restarted-after-ps2-controller-communication-in-arduino
108 |
109 | if (success) {
110 | // переводим диапазон 0..255 в -MAX_SPEED..MAX_SPEED
111 | int valLX = map(ps2x.Analog(PSS_LX), 0, 256, -MAX_SPEED, MAX_SPEED);
112 | int valLY = map(ps2x.Analog(PSS_LY), 256, 0, -MAX_SPEED, MAX_SPEED); // инвертируем
113 | int valRX = map(ps2x.Analog(PSS_RX), 0, 256, -MAX_SPEED, MAX_SPEED);
114 | int valRY = map(ps2x.Analog(PSS_RY), 256, 0, -MAX_SPEED, MAX_SPEED); // инвертируем
115 |
116 | int dutyFR = valLY + valLX;
117 | int dutyFL = valLY - valLX;
118 | int dutyBR = valLY - valLX;
119 | int dutyBL = valLY + valLX;
120 |
121 | dutyFR += valRY - valRX;
122 | dutyFL += valRY + valRX;
123 | dutyBR += valRY - valRX;
124 | dutyBL += valRY + valRX;
125 |
126 | // ПЛАВНЫЙ контроль скорости, защита от рывков
127 | motorFR.smoothTick(dutyFR);
128 | motorBR.smoothTick(dutyBR);
129 | motorFL.smoothTick(dutyFL);
130 | motorBL.smoothTick(dutyBL);
131 | } else {
132 | // страшно, вырубай
133 | motorFR.setSpeed(0);
134 | motorBR.setSpeed(0);
135 | motorFL.setSpeed(0);
136 | motorBL.setSpeed(0);
137 | }
138 | delay(50);
139 | }
140 |
--------------------------------------------------------------------------------
/firmware/mecanum_ps2_opto/encoder.h:
--------------------------------------------------------------------------------
1 | class encCounter {
2 | public:
3 | encCounter(byte pin) {
4 | _pin = pin;
5 | }
6 | long update(int direction) { // приняли
7 | bool curState = pinRead(_pin); // опрос
8 | if (_lastState != curState) { // словили изменение
9 | _lastState = curState;
10 | if (curState) { // по фронту
11 | _counter += direction; // запомнили поворот
12 | }
13 | }
14 | return _counter; // вернули
15 | }
16 |
17 | private:
18 | long _counter = 0;
19 | byte _pin;
20 | bool _lastState = 0;
21 | // быстрый digitalRead для atmega328
22 | bool pinRead(uint8_t pin) {
23 | if (pin < 8) {
24 | return bitRead(PIND, pin);
25 | } else if (pin < 14) {
26 | return bitRead(PINB, pin - 8);
27 | } else if (pin < 20) {
28 | return bitRead(PINC, pin - 14);
29 | }
30 | }
31 | };
32 |
--------------------------------------------------------------------------------
/firmware/mecanum_ps2_opto/mecanum_ps2_opto.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Скетч к проекту "Телега на всенаправленных колёсах"
3 | - Страница проекта (схемы, описания): https://alexgyver.ru/mecanumbot
4 | - Исходники на GitHub: https://github.com/AlexGyver/MecanumBot/
5 | Проблемы с загрузкой? Читай гайд для новичков: https://alexgyver.ru/arduino-first/
6 | Нравится, как написан код? Поддержи автора! https://alexgyver.ru/support_alex/
7 | AlexGyver, AlexGyver Technologies, 2020
8 | https://www.youtube.com/c/alexgyvershow
9 | https://github.com/AlexGyver
10 | https://AlexGyver.ru/
11 | alex@alexgyver.ru
12 | */
13 |
14 | #define MAX_SPEED 70 // максимальная скорость моторов, в тиках в секунду!
15 | #define MIN_DUTY 50 // мин. сигнал, при котором мотор начинает движение
16 | #define STEP_SIZE 50 // перемещение по кнопкам крестовины (в тиках)
17 | #define ACCEL 7 // ускорение
18 | #define MAX_FOLLOW_SPEED 500 // макс. скорость
19 |
20 | // коэффициенты ПИД
21 | #define PID_P 2.2
22 | #define PID_I 0.4
23 | #define PID_D 0.01
24 |
25 | // пины энкодеров
26 | #define OPTO_FL 10
27 | #define OPTO_FR 11
28 | #define OPTO_BL 12
29 | #define OPTO_BR 13
30 |
31 | #define MOTOR_TEST 0 // тест моторов
32 | // при запуске крутятся ВПЕРЁД по очереди:
33 | // FL - передний левый
34 | // FR - передний правый
35 | // BL - задний левый
36 | // BR - задний правый
37 |
38 | // пины драйверов (_B должен быть ШИМ)
39 | #define MOTOR1_A 2
40 | #define MOTOR1_B 3 // ШИМ!
41 | #define MOTOR2_A 4
42 | #define MOTOR2_B 5 // ШИМ!
43 | #define MOTOR3_A 7
44 | #define MOTOR3_B 6 // ШИМ!
45 | #define MOTOR4_A 8
46 | #define MOTOR4_B 9 // ШИМ!
47 |
48 | #include
49 | // тут можно поменять моторы местами
50 | AccelMotor motorBL(DRIVER2WIRE, MOTOR1_A, MOTOR1_B, HIGH);
51 | AccelMotor motorFL(DRIVER2WIRE, MOTOR2_A, MOTOR2_B, HIGH);
52 | AccelMotor motorFR(DRIVER2WIRE, MOTOR3_A, MOTOR3_B, HIGH);
53 | AccelMotor motorBR(DRIVER2WIRE, MOTOR4_A, MOTOR4_B, HIGH);
54 |
55 | // пины ресивера ps2
56 | #define PS2_DAT A0
57 | #define PS2_CMD A1
58 | #define PS2_SEL A2
59 | #define PS2_CLK A3
60 |
61 | #include
62 | PS2X ps2x;
63 |
64 | #include "encoder.h" // мини-класс для щелевого датчика
65 | encCounter encFL(OPTO_FL);
66 | encCounter encFR(OPTO_FR);
67 | encCounter encBL(OPTO_BL);
68 | encCounter encBR(OPTO_BR);
69 |
70 | void setup() {
71 | attachPCINT(OPTO_FL);
72 | attachPCINT(OPTO_FR);
73 | attachPCINT(OPTO_BL);
74 | attachPCINT(OPTO_BR);
75 |
76 | Serial.begin(9600);
77 | // чуть подразгоним ШИМ https://alexgyver.ru/lessons/pwm-overclock/
78 | // Пины D3 и D11 - 980 Гц
79 | TCCR2B = 0b00000100; // x64
80 | TCCR2A = 0b00000011; // fast pwm
81 |
82 | // Пины D9 и D10 - 976 Гц
83 | TCCR1A = 0b00000001; // 8bit
84 | TCCR1B = 0b00001011; // x64 fast pwm
85 |
86 | // тест моторов
87 | #if (MOTOR_TEST == 1)
88 | Serial.println("front left");
89 | motorFL.run(FORWARD, 100);
90 | delay(3000);
91 | motorFL.run(STOP);
92 | delay(1000);
93 | Serial.println("front right");
94 | motorFR.run(FORWARD, 100);
95 | delay(3000);
96 | motorFR.run(STOP);
97 | delay(1000);
98 | Serial.println("back left");
99 | motorBL.run(FORWARD, 100);
100 | delay(3000);
101 | motorBL.run(STOP);
102 | delay(1000);
103 | Serial.println("back right");
104 | motorBR.run(FORWARD, 100);
105 | delay(3000);
106 | motorBR.run(STOP);
107 | #endif
108 | // минимальный сигнал на мотор
109 | motorFR.setMinDuty(MIN_DUTY);
110 | motorBR.setMinDuty(MIN_DUTY);
111 | motorFL.setMinDuty(MIN_DUTY);
112 | motorBL.setMinDuty(MIN_DUTY);
113 |
114 | motorFR.setMode(AUTO);
115 | motorBR.setMode(AUTO);
116 | motorFL.setMode(AUTO);
117 | motorBL.setMode(AUTO);
118 |
119 | // период интегрирования
120 | motorFR.setDt(30);
121 | motorBR.setDt(30);
122 | motorFL.setDt(30);
123 | motorBL.setDt(30);
124 |
125 | // режим управления мотора в PID_SPEED
126 | motorFR.setRunMode(PID_SPEED);
127 | motorBR.setRunMode(PID_SPEED);
128 | motorFL.setRunMode(PID_SPEED);
129 | motorBL.setRunMode(PID_SPEED);
130 |
131 | // ускорение для следования позиции
132 | motorFR.setAcceleration(ACCEL);
133 | motorFL.setAcceleration(ACCEL);
134 | motorBR.setAcceleration(ACCEL);
135 | motorBL.setAcceleration(ACCEL);
136 |
137 | // макс. скорость для следования позиции
138 | motorFR.setMaxSpeed(MAX_FOLLOW_SPEED);
139 | motorFL.setMaxSpeed(MAX_FOLLOW_SPEED);
140 | motorBR.setMaxSpeed(MAX_FOLLOW_SPEED);
141 | motorBL.setMaxSpeed(MAX_FOLLOW_SPEED);
142 |
143 | // точность следования к позиции
144 | motorFR.setStopZone(5);
145 | motorFL.setStopZone(5);
146 | motorBR.setStopZone(5);
147 | motorBL.setStopZone(5);
148 |
149 | // ПИДы
150 | motorFR.kp = PID_P;
151 | motorFL.kp = PID_P;
152 | motorBR.kp = PID_P;
153 | motorBL.kp = PID_P;
154 |
155 | motorFR.ki = PID_I;
156 | motorFL.ki = PID_I;
157 | motorBR.ki = PID_I;
158 | motorBL.ki = PID_I;
159 |
160 | motorFR.kd = PID_D;
161 | motorFL.kd = PID_D;
162 | motorBR.kd = PID_D;
163 | motorBL.kd = PID_D;
164 |
165 | delay(1000); // ждём запуска контроллера
166 | ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT, false, false);
167 | }
168 |
169 | bool currentMode = false; // false скорость, true позиция
170 | long posFR = 0;
171 | long posBR = 0;
172 | long posFL = 0;
173 | long posBL = 0;
174 |
175 | // функция переключает между режимом удержания скорости
176 | // и следованием к позиции
177 | void changeMode(bool mode) {
178 | currentMode = mode;
179 | if (mode) {
180 | motorFR.setRunMode(ACCEL_POS);
181 | motorBR.setRunMode(ACCEL_POS);
182 | motorFL.setRunMode(ACCEL_POS);
183 | motorBL.setRunMode(ACCEL_POS);
184 |
185 | // обновляем буфер позиции
186 | posFR = motorFR.getCurrent();
187 | posFL = motorFL.getCurrent();
188 | posBR = motorBR.getCurrent();
189 | posBL = motorBL.getCurrent();
190 | } else {
191 | motorFR.setRunMode(PID_SPEED);
192 | motorBR.setRunMode(PID_SPEED);
193 | motorFL.setRunMode(PID_SPEED);
194 | motorBL.setRunMode(PID_SPEED);
195 | }
196 | }
197 |
198 | void updatePos() {
199 | motorFR.setTarget(posFR);
200 | motorBR.setTarget(posBR);
201 | motorFL.setTarget(posFL);
202 | motorBL.setTarget(posBL);
203 | }
204 |
205 | void loop() {
206 | static uint32_t tmr;
207 | if (millis() - tmr >= 50) {
208 | tmr += 50;
209 | bool success = ps2x.read_gamepad(false, 0); // читаем
210 | ps2x.reconfig_gamepad(); // костыль https://stackoverflow.com/questions/46493222/why-arduino-needs-to-be-restarted-after-ps2-controller-communication-in-arduino
211 |
212 | if (success) {
213 | if (ps2x.ButtonPressed(PSB_PAD_LEFT)) {
214 | changeMode(true);
215 | posFR -= STEP_SIZE;
216 | posFL += STEP_SIZE;
217 | posBR += STEP_SIZE;
218 | posBL -= STEP_SIZE;
219 | updatePos();
220 | }
221 | if (ps2x.ButtonPressed(PSB_PAD_RIGHT)) {
222 | changeMode(true);
223 | posFR += STEP_SIZE;
224 | posFL -= STEP_SIZE;
225 | posBR -= STEP_SIZE;
226 | posBL += STEP_SIZE;
227 | updatePos();
228 | }
229 | if (ps2x.ButtonPressed(PSB_PAD_UP)) {
230 | changeMode(true);
231 | posFR += STEP_SIZE;
232 | posFL += STEP_SIZE;
233 | posBR += STEP_SIZE;
234 | posBL += STEP_SIZE;
235 | updatePos();
236 | }
237 | if (ps2x.ButtonPressed(PSB_PAD_DOWN)) {
238 | changeMode(true);
239 | posFR -= STEP_SIZE;
240 | posFL -= STEP_SIZE;
241 | posBR -= STEP_SIZE;
242 | posBL -= STEP_SIZE;
243 | updatePos();
244 | }
245 |
246 | if (!currentMode) {
247 | // переводим диапазон 0..255 в -MAX_SPEED..MAX_SPEED
248 | int valLX = map(ps2x.Analog(PSS_LX), 0, 256, -MAX_SPEED, MAX_SPEED);
249 | int valLY = map(ps2x.Analog(PSS_LY), 256, 0, -MAX_SPEED, MAX_SPEED); // инвертируем ось
250 | int valRX = map(ps2x.Analog(PSS_RX), 0, 256, -MAX_SPEED, MAX_SPEED);
251 | int valRY = map(ps2x.Analog(PSS_RY), 256, 0, -MAX_SPEED, MAX_SPEED); // инвертируем ось
252 |
253 | int dutyFR = valLY + valLX;
254 | int dutyFL = valLY - valLX;
255 | int dutyBR = valLY - valLX;
256 | int dutyBL = valLY + valLX;
257 |
258 | dutyFR += valRY - valRX;
259 | dutyFL += valRY + valRX;
260 | dutyBR += valRY - valRX;
261 | dutyBL += valRY + valRX;
262 |
263 | // ПИД контроль скорости
264 | motorFR.setTargetSpeed(dutyFR);
265 | motorBR.setTargetSpeed(dutyBR);
266 | motorFL.setTargetSpeed(dutyFL);
267 | motorBL.setTargetSpeed(dutyBL);
268 |
269 | Serial.print(motorFL.getSpeed());
270 | Serial.print(',');
271 | Serial.print(motorFL.getDuty());
272 | Serial.print(',');
273 | Serial.println(motorFL.getTargetSpeed());
274 | } else {
275 | Serial.print(motorFL.getCurrent());
276 | Serial.print(',');
277 | Serial.print(motorFL.getDuty());
278 | Serial.print(',');
279 | Serial.println(motorFL.getTarget());
280 | }
281 | } else {
282 | // страшно, вырубай
283 | motorFR.setSpeed(0);
284 | motorBR.setSpeed(0);
285 | motorFL.setSpeed(0);
286 | motorBL.setSpeed(0);
287 | }
288 |
289 | }
290 | bool m1 = motorFR.tick(encFR.update(motorFR.getState()));
291 | bool m2 = motorBR.tick(encBR.update(motorBR.getState()));
292 | bool m3 = motorFL.tick(encFL.update(motorFL.getState()));
293 | bool m4 = motorBL.tick(encBL.update(motorBL.getState()));
294 |
295 | // включаем управление скоростью стиками, если все моторы "приехали"
296 | if (currentMode && !m1 && !m2 && !m3 && !m4) {
297 | changeMode(false);
298 | }
299 | }
300 |
301 | // вектор PCint
302 | ISR(PCINT0_vect) { // пины 8-13
303 | encFR.update(motorFR.getState());
304 | encBR.update(motorBR.getState());
305 | encFL.update(motorFL.getState());
306 | encBL.update(motorBL.getState());
307 | }
308 |
309 | // функция для настройки PCINT
310 | uint8_t attachPCINT(uint8_t pin) {
311 | if (pin < 8) { // D0-D7 (PCINT2)
312 | PCICR |= (1 << PCIE2);
313 | PCMSK2 |= (1 << pin);
314 | return 2;
315 | } else if (pin > 13) { //A0-A5 (PCINT1)
316 | PCICR |= (1 << PCIE1);
317 | PCMSK1 |= (1 << pin - 14);
318 | return 1;
319 | } else { // D8-D13 (PCINT0)
320 | PCICR |= (1 << PCIE0);
321 | PCMSK0 |= (1 << pin - 8);
322 | return 0;
323 | }
324 | }
325 |
--------------------------------------------------------------------------------
/libraries/AccelMotor/AccelMotor.cpp:
--------------------------------------------------------------------------------
1 | #include "AccelMotor.h"
2 | #define _sign(x) ((x) > 0 ? 1 : -1)
3 |
4 | bool AccelMotor::tick(long pos) {
5 | _currentPos = pos;
6 | if (millis() - _tmr2 > _dt) {
7 | _tmr2 += _dt;
8 | _curSpeed = (long)(_currentPos - _lastPos) / _dts; // ищем скорость в тиках/секунду
9 | _curSpeed = filter(_curSpeed); // медиана + RA
10 | _lastPos = _currentPos;
11 |
12 | switch (_runMode) {
13 | case ACCEL_POS:
14 | {
15 | long err = _targetPos - controlPos; // "ошибка" позиции
16 | if (err != 0) {
17 | float accelDt = _accel * _dts;
18 | float accel = accelDt;
19 | if (abs(err) < _stopzone && abs(_lastSpeed - controlSpeed) < 2) { // условие завершения движения
20 | controlPos = _targetPos;
21 | controlSpeed = 0;
22 | accel = 0;
23 | }
24 | if (abs(err) < (float)(controlSpeed * controlSpeed) / (2.0 * accelDt)) { // если пора тормозить
25 | err = -err; // разворачиваем ускорение
26 | accel = (float)(controlSpeed * controlSpeed) / (2.0 * abs(err)); // пересчёт ускорения для плавности
27 | if (_sign(controlSpeed) == _sign(err)) err = -err; // поворачивай обратно
28 | }
29 | controlSpeed += accel * _sign(err); // применяем ускорение
30 | controlSpeed = constrain(controlSpeed, -_maxSpeed*_dts, _maxSpeed*_dts); // ограничим
31 | controlPos += controlSpeed; // двигаем позицию
32 | _lastSpeed = controlSpeed;
33 |
34 | }
35 | PIDcontrol(controlPos, _currentPos, true);
36 | }
37 | break;
38 | case PID_POS:
39 | PIDcontrol(_targetPos, _currentPos, true);
40 | break;
41 | case ACCEL_SPEED:
42 | {
43 | int err = _targetSpeed - _curSpeed; // ошибка скорости
44 | float reducer = min(abs(err) / _accel, 1.0); // уменьшает ускорение, если шаг будет дальше чем установка
45 | _dutyF += (float)_sign(err) * _accel * _dts * reducer; // ускоряем/замедляем
46 | _dutyF = constrain(_dutyF, -_maxDuty, _maxDuty); // ограничитель 8/10 бит
47 | setSpeed(_dutyF);
48 | }
49 | break;
50 | case PID_SPEED:
51 | PIDcontrol(_targetSpeed, _curSpeed, false);
52 | break;
53 | }
54 | }
55 | if (_runMode > 1) return (getState() != 0);
56 | else return (getState() != 0 || abs(_targetPos - _currentPos) > _stopzone);
57 | }
58 |
59 | void AccelMotor::PIDcontrol(long target, long current, bool cutoff) {
60 | // cutoff нужен только для стабилизации позиции, обнуляет integral и учитывает мёртвую зону мотора
61 | long err = target - current;
62 | _dutyF = err * kp; // P составляющая
63 | _dutyF += (float)(_prevInput - current) * kd / _dts; // D составляющая
64 | _prevInput = current;
65 | integral += (float)err * ki * _dts;
66 | _dutyF += integral; // I составляющая
67 | if (cutoff) { // отсечка
68 | if (abs(err) > _stopzone) _dutyF += _sign(err)*_minDuty; // учитываем _minDuty - мёртвую зону мотора (метод setMinDuty)
69 | else integral = 0;
70 | } else {
71 | if (err == 0 && target == 0) integral = 0;
72 | else _dutyF += _sign(err)*_minDuty;
73 | }
74 | _dutyF = constrain(_dutyF, -_maxDuty, _maxDuty); // ограничиваем по 8 или 10 бит
75 | setSpeed(_dutyF); // и поехали
76 | }
77 |
78 | bool AccelMotor::isBlocked() {
79 | return (abs(_dutyF) > _minDuty && _curSpeed == 0);
80 | }
81 |
82 | // ===== settings =====
83 | void AccelMotor::setRatio(float ratio) {
84 | _ratio = ratio;
85 | }
86 | void AccelMotor::setDt(int dt) {
87 | _dt = dt;
88 | _dts = dt / 1000.0;
89 | }
90 | void AccelMotor::setCurrent(long pos) {
91 | _currentPos = pos;
92 | }
93 | void AccelMotor::setRunMode(runMode mode) {
94 | _runMode = mode;
95 | if (mode == ACCEL_POS) controlPos = _currentPos; // костыль!
96 | }
97 |
98 | // ===== current position =====
99 | long AccelMotor::getCurrent() {
100 | return _currentPos;
101 | }
102 | long AccelMotor::getCurrentDeg() {
103 | return (long)_currentPos * 360 / _ratio;
104 | }
105 |
106 | // ===== current speed =====
107 | int AccelMotor::getSpeed() {
108 | return _curSpeed;
109 | }
110 | int AccelMotor::getSpeedDeg() {
111 | return (long)_curSpeed * 360 / _ratio;
112 | }
113 | float AccelMotor::getDuty() {
114 | return _dutyF;
115 | }
116 |
117 | // ===== target position mode =====
118 | void AccelMotor::setTarget(long pos) {
119 | _targetPos = pos;
120 | }
121 | void AccelMotor::setTargetDeg(long pos) {
122 | _targetPos = (long)pos * _ratio / 360;
123 | }
124 | long AccelMotor::getTarget() {
125 | return _targetPos;
126 | }
127 | long AccelMotor::getTargetDeg() {
128 | return (long)_targetPos * 360 / _ratio;
129 | }
130 |
131 | void AccelMotor::setStopZone(int zone) {
132 | _stopzone = zone;
133 | }
134 |
135 | // ===== target speed mode =====
136 | void AccelMotor::setTargetSpeed(int speed) {
137 | _targetSpeed = speed;
138 | }
139 | void AccelMotor::setTargetSpeedDeg(int speed) {
140 | _targetSpeed = (long)speed * _ratio / 360;
141 | }
142 | int AccelMotor::getTargetSpeed() {
143 | return _targetSpeed;
144 | }
145 | int AccelMotor::getTargetSpeedDeg() {
146 | return (long)_targetSpeed * 360 / _ratio;
147 | }
148 |
149 | // ===== max speed / acceleration =====
150 | void AccelMotor::setMaxSpeed(int speed) {
151 | _maxSpeed = speed;
152 | }
153 | void AccelMotor::setMaxSpeedDeg(int speed) {
154 | _maxSpeed = (long)speed * _ratio / 360;
155 | }
156 | void AccelMotor::setAcceleration(float accel) {
157 | _accel = accel;
158 | }
159 | void AccelMotor::setAccelerationDeg(float accel) {
160 | _accel = (float)accel * _ratio / 360.0;
161 | }
162 |
163 | // ==== filter ====
164 | int AccelMotor::filter(int newVal) {
165 | _buf[_count] = newVal;
166 | if (++_count >= 3) _count = 0;
167 | int middle = 0;
168 | if ((_buf[0] <= _buf[1]) && (_buf[0] <= _buf[2])) {
169 | middle = (_buf[1] <= _buf[2]) ? _buf[1] : _buf[2];
170 | } else {
171 | if ((_buf[1] <= _buf[0]) && (_buf[1] <= _buf[2])) {
172 | middle = (_buf[0] <= _buf[2]) ? _buf[0] : _buf[2];
173 | }
174 | else {
175 | middle = (_buf[0] <= _buf[1]) ? _buf[0] : _buf[1];
176 | }
177 | }
178 | _middle_f += (middle-_middle_f) * 0.7;
179 | return _middle_f;
180 | }
181 |
--------------------------------------------------------------------------------
/libraries/AccelMotor/AccelMotor.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 | #include
3 | #include
4 |
5 | // БЕТА! ЭТО БЕТА! beta 0.0000 кек
6 |
7 | /*
8 | Библиотека для расширенного управления и стабилизации мотора с энкодером
9 | - Наследует все фишки из библиотеки GyverMotor (поддержка разных драйверов и режимов)
10 | - Режим поддержания скорости с обратной связью
11 | - Режим поворота на заданный угол с обратной связью
12 | - Настраиваемые коэффициенты PID регулятора
13 | - Ограничение ускорения и скорости
14 | - Библиотека принимает любой тип обратной связи: энкодер, потенциометр, и т.д.
15 | - Поддержка мотор-редукторов, настройка передаточного отношения энкодера
16 | - Регулятор учитывает "мёртвую зону" мотора
17 | - Все функции работают в градусах и "тиках" энкодера
18 | */
19 |
20 | enum runMode {
21 | ACCEL_POS,
22 | PID_POS,
23 | ACCEL_SPEED,
24 | PID_SPEED,
25 | IDLE_RUN,
26 | };
27 |
28 | class AccelMotor : public GMotor {
29 | public:
30 | using GMotor::GMotor;
31 |
32 | // управляет мотором. Вызывать как можно чаще (внутри таймер с периодом dt)
33 | // принимает текущее положение вала мотора (по счёту энкодера)
34 | // возвращает true если мотор всё ещё движется к цели
35 | bool tick(long pos);
36 |
37 | // установка передаточного отношения редуктора и энкодера
38 | // пример: если редуктор 1:30 - передаём в функцию 30
39 | // пример: если редуктор 1:30 и энкодер на 12 тиков - передаём 30*12
40 | void setRatio(float ratio);
41 |
42 | // установка периода регулятора (рекомендуется 2-50 миллисекунд)
43 | void setDt(int dt);
44 |
45 | // установка и получение текущей позиции в тиках энкодера и градусах.
46 | // setCurrent(pos) равносильна вызову tick(pos) и в принципе не нужна!
47 | void setCurrent(long pos);
48 | long getCurrent();
49 | long getCurrentDeg();
50 |
51 | // установка и получение целевой позиции в тиках энкодера и градусах
52 | void setTarget(long pos);
53 | void setTargetDeg(long pos);
54 | long getTarget();
55 | long getTargetDeg();
56 |
57 | // установка максимальной скорости в тиках энкодера/секунду и градусах/секунду
58 | void setMaxSpeed(int speed);
59 | void setMaxSpeedDeg(int speed);
60 |
61 | // установка ускорения тиках энкодера и градусах в секунду
62 | void setAcceleration(float accel);
63 | void setAccelerationDeg(float accel);
64 |
65 | // установка и получение целевой скорости в тиках энкодера/секунду и градусах/секунду
66 | void setTargetSpeed(int speed);
67 | void setTargetSpeedDeg(int speed);
68 | int getTargetSpeed();
69 | int getTargetSpeedDeg();
70 |
71 | // получить текущую скорость в тиках энкодера/секунду и градусах/секунду
72 | int getSpeed();
73 | int getSpeedDeg();
74 |
75 | // получить текущий ШИМ сигнал (float из ПИД регулятора)
76 | float getDuty();
77 |
78 | // ручная установка режима работы
79 | // IDLE_RUN - tick() не управляет мотором. Может использоваться для отладки
80 | // ACCEL_POS - tick() работает в режиме плавного следования к целевому углу
81 | // PID_POS - tick() работает в режиме резкого следования к целевому углу
82 | // ACCEL_SPEED - tick() работает в режиме плавного поддержания скорости (с заданным ускорением)
83 | // PID_SPEED - tick() работает в режиме поддержания скорости по ПИД регулятору
84 | void setRunMode(runMode mode);
85 |
86 | // возвращает true, если вал мотора заблокирован, а сигнал подаётся
87 | bool isBlocked();
88 |
89 | // коэффициенты ПИД регулятора
90 | // пропорциональный - от него зависит агрессивность управления, нужно увеличивать kp
91 | // при увеличении нагрузки на вал, чтобы регулятор подавал больший управляющий ШИМ сигнал
92 | float kp = 2.0;
93 |
94 | // интегральный - позволяет нивелировать ошибку со временем, имеет накопительный эффект
95 | float ki = 0.9;
96 |
97 | // дифференциальный. Позволяет чуть сгладить рывки, но при большом значении
98 | // сам становится причиной рывков и раскачки системы!
99 | float kd = 0.1;
100 |
101 | // установить зону остановки мотора для режима стабилизации позиции (по умолч. 8)
102 | void setStopZone(int zone);
103 |
104 | private:
105 | int filter(int newVal);
106 | int _buf[3];
107 | byte _count = 0;
108 | float _middle_f = 0;
109 |
110 | float _lastSpeed = 0;
111 | void PIDcontrol(long target, long current, bool cutoff);
112 | float integral = 0;
113 | int _dt = 20;
114 | float _dts = 0.02;
115 | long _lastPos = 0, _currentPos = 0, _targetPos = 0;
116 | int _curSpeed = 0;
117 | int _maxSpeed = 0, _targetSpeed = 0;
118 | float _ratio = 1;
119 | uint32_t _tmr2 = 0;
120 | float _accel = 1;
121 | float _dutyF = 0;
122 | long controlPos = 0;
123 | float controlSpeed = 0;
124 | int _stopzone = 8;
125 | long _prevInput = 0;
126 | runMode _runMode = IDLE_RUN;
127 | };
128 |
129 | /*
130 | ======= НАСЛЕДУЕТСЯ ИЗ GYVERMOTOR =======
131 | GMotor(driverType type, int8_t param1 = NC, int8_t param2 = NC, int8_t param3 = NC, int8_t param4 = NC);
132 | // три варианта создания объекта в зависимости от драйвера:
133 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW/HIGH) )
134 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
135 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
136 |
137 | // установка скорости 0-255 (8 бит) и 0-1023 (10 бит)
138 | void setSpeed(int16_t duty);
139 |
140 | // сменить режим работы мотора:
141 | // FORWARD - вперёд
142 | // BACKWARD - назад
143 | // STOP - остановить
144 | // BRAKE - активное торможение
145 | void setMode(workMode mode);
146 |
147 | // направление вращения
148 | // NORM - обычное
149 | // REVERSE - обратное
150 | void setDirection(dir direction);
151 |
152 | // установить минимальную скважность (при которой мотор начинает крутиться)
153 | void setMinDuty(int duty);
154 |
155 | // установить выход в 8 бит
156 | void set8bitMode();
157 |
158 | // установить выход в 10 бит
159 | void set10bitMode();
160 |
161 | // установить deadtime (в микросекундах). По умолч 0
162 | void setDeadtime(uint16_t deadtime);
163 |
164 | // установить уровень драйвера (по умолч. HIGH)
165 | void setLevel(int8_t level);
166 |
167 | // плавное изменение к указанной скорости (к величине ШИМ)
168 | void smoothTick(int16_t duty);
169 |
170 | // скорость изменения скорости
171 | void setSmoothSpeed(uint8_t speed);
172 |
173 | // дать прямую команду мотору (без смены режима)
174 | void run(workMode mode, int16_t duty);
175 |
176 | // возвращает -1 при вращении BACKWARD, 1 при FORWARD и 0 при остановке и торможении
177 | int getState();
178 | */
--------------------------------------------------------------------------------
/libraries/AccelMotor/docs/jga25.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/AlexGyver/MecanumBot/dfd2164ae9db8b4dd4962f0753cf5bd1c7a2e279/libraries/AccelMotor/docs/jga25.jpg
--------------------------------------------------------------------------------
/libraries/AccelMotor/keywords.txt:
--------------------------------------------------------------------------------
1 | #######################################
2 | # Syntax Coloring Map For AccelMotor
3 | #######################################
4 |
5 | #######################################
6 | # Datatypes (KEYWORD1)
7 | #######################################
8 | AccelMotor KEYWORD1
9 |
10 | #######################################
11 | # Methods and Functions (KEYWORD2)
12 | #######################################
13 | tick KEYWORD2
14 | setRatio KEYWORD2
15 | setDt KEYWORD2
16 | setCurrent KEYWORD2
17 | getCurrent KEYWORD2
18 | getCurrentDeg KEYWORD2
19 | setTarget KEYWORD2
20 | setTargetDeg KEYWORD2
21 | getTarget KEYWORD2
22 | getTargetDeg KEYWORD2
23 | setMaxSpeed KEYWORD2
24 | setMaxSpeedDeg KEYWORD2
25 | setAcceleration KEYWORD2
26 | setAccelerationDeg KEYWORD2
27 | setTargetSpeed KEYWORD2
28 | setTargetSpeedDeg KEYWORD2
29 | getTargetSpeed KEYWORD2
30 | getTargetSpeedDeg KEYWORD2
31 | getSpeed KEYWORD2
32 | getSpeedDeg KEYWORD2
33 | getDuty KEYWORD2
34 | setRunMode KEYWORD2
35 | setStopZone KEYWORD2
36 | isBlocked KEYWORD2
37 | kp KEYWORD2
38 | ki KEYWORD2
39 | kd KEYWORD2
40 |
41 | #######################################
42 | # Constants (LITERAL1)
43 | #######################################
44 |
45 | IDLE_RUN LITERAL1
46 | ACCEL_POS LITERAL1
47 | PID_POS LITERAL1
48 | ACCEL_SPEED LITERAL1
49 | PID_SPEED LITERAL1
--------------------------------------------------------------------------------
/libraries/AccelMotor/library.properties:
--------------------------------------------------------------------------------
1 | name=AccelMotor
2 | version=0.0
3 | author=AlexGyver
4 | maintainer=AlexGyver
5 | sentence=Library for motor smooth control
6 | paragraph=Simple motor speed and position controller
7 | category=Device Control
8 | url=https://github.com/AlexGyver/GyverLibs
9 | architectures=*
--------------------------------------------------------------------------------
/libraries/GyverMotor/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2021 Alex
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/README.md:
--------------------------------------------------------------------------------
1 | [](#versions)
2 | [](https://alexgyver.ru/)
3 | [](https://alexgyver.ru/support_alex/)
4 |
5 | # GyverMotor
6 | Библиотека для удобного управления коллекторными моторами через драйвер
7 | - Контроль скорости и направления вращения
8 | - Работа с ШИМ любого разрешения
9 | - Плавный пуск и изменение скорости
10 | - Активный тормоз
11 | - Порог минимального ШИМ
12 | - Deadtime
13 | - Поддержка 5 типов драйверов
14 |
15 | > Библиотека "состоит" из двух библиотек: GyverMotor и GyverMotor2. Вторая версия новее, легче, лучше оптимизирована и проще в использовании!
16 |
17 | ### Совместимость
18 | Совместима со всеми Arduino платформами (используются Arduino-функции)
19 | - Для esp8266 (до SDK v2.7.4) не забудь переключить управление в 10 бит!
20 |
21 | ### Документация
22 | К библиотеке есть [расширенная документация](https://alexgyver.ru/GyverMotor/)
23 |
24 | ## Содержание
25 | - [Установка](#install)
26 | - [Инициализация](#init)
27 | - [Использование](#usage)
28 | - [Пример](#example)
29 | - [Версии](#versions)
30 | - [Баги и обратная связь](#feedback)
31 |
32 |
33 | ## Установка
34 | - Библиотеку можно найти по названию **GyverMotor** и установить через менеджер библиотек в:
35 | - Arduino IDE
36 | - Arduino IDE v2
37 | - PlatformIO
38 | - [Скачать библиотеку](https://github.com/GyverLibs/GyverMotor/archive/refs/heads/main.zip) .zip архивом для ручной установки:
39 | - Распаковать и положить в *C:\Program Files (x86)\Arduino\libraries* (Windows x64)
40 | - Распаковать и положить в *C:\Program Files\Arduino\libraries* (Windows x32)
41 | - Распаковать и положить в *Документы/Arduino/libraries/*
42 | - (Arduino IDE) автоматическая установка из .zip: *Скетч/Подключить библиотеку/Добавить .ZIP библиотеку…* и указать скачанный архив
43 | - Читай более подробную инструкцию по установке библиотек [здесь](https://alexgyver.ru/arduino-first/#%D0%A3%D1%81%D1%82%D0%B0%D0%BD%D0%BE%D0%B2%D0%BA%D0%B0_%D0%B1%D0%B8%D0%B1%D0%BB%D0%B8%D0%BE%D1%82%D0%B5%D0%BA)
44 |
45 |
46 | ## Инициализация
47 | Типы драйверов:
48 | - **DRIVER2WIRE** - двухпроводной драйвер с инверсией шим (dir + PWM)
49 | - **DRIVER2WIRE_NO_INVERT** - двухпроводной драйвер без инверсии ШИМ (dir + PWM)
50 | - **DRIVER2WIRE_PWM** - двухпроводной драйвер с двумя ШИМ (PWM + PWM)
51 | - **DRIVER3WIRE** - трёхпроводной драйвер (dir + dir + PWM)
52 | - **RELAY2WIRE** - реле в качестве драйвера (dir + dir)
53 |
54 | Для двухпроводных мостовых драйверов стоит отдавать предпочтение типу **DRIVER2WIRE_PWM**. Он требует два ШИМ пина,
55 | но драйвер работает более правильно и меньше нагружается, а также скорость будет одинаковая в обе стороны. В отличие от простого **DRIVER2WIRE**.
56 |
57 |
58 | GyverMotor
59 |
60 | ```cpp
61 | // варианты инициализации в зависимости от типа драйвера:
62 | GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) );
63 | GMotor motor(DRIVER2WIRE_NO_INVERT, dig_pin, PWM_pin, (LOW / HIGH) );
64 | GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) );
65 | GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) );
66 | /*
67 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
68 | PWM_pin - любой ШИМ пин МК
69 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
70 | */
71 | ```
72 |
73 |
74 |
75 | GyverMotor2
76 |
77 | ```cpp
78 | GMotor2<тип> motor(пин1, пин2, пин3); // разрядность ШИМ 8 бит (0.. 255)
79 | GMotor2<тип, разрядность> motor(пин1, пин2, пин3); // общий случай, разрядность ШИМ в битах
80 |
81 | // типы и количество пинов в зависимости от драйвера
82 | GMotor2 motor(GPIO, PWM);
83 | GMotor2 motor(GPIO, PWM);
84 | GMotor2 motor(PWM, PWM);
85 | GMotor2 motor(GPIO, GPIO, PWM);
86 | GMotor2 motor(GPIO, GPIO);
87 | ```
88 |
89 |
90 |
91 | ## Использование
92 |
93 | GyverMotor
94 |
95 | ```cpp
96 | GMotor(GM_driverType type, int8_t param1 = _GM_NC, int8_t param2 = _GM_NC, int8_t param3 = _GM_NC, int8_t param4 = _GM_NC);
97 | // три варианта создания объекта в зависимости от драйвера:
98 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW/HIGH) )
99 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
100 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
101 |
102 | // установка скорости -255..255 (8 бит) и -1023..1023 (10 бит)
103 | void setSpeed(int16_t duty);
104 |
105 | // сменить режим работы мотора:
106 | // FORWARD - вперёд
107 | // BACKWARD - назад
108 | // STOP - остановить
109 | // BRAKE - активный тормоз
110 | // AUTO - подчиняется setSpeed (-255.. 255)
111 | void setMode(GM_workMode mode);
112 |
113 | // направление вращения
114 | // NORM - обычное
115 | // REVERSE - обратное
116 | void setDirection(bool direction);
117 |
118 | // установить минимальную скважность (при которой мотор начинает крутиться)
119 | void setMinDuty(int duty);
120 |
121 | // установить разрешение ШИМ в битах
122 | void setResolution(byte bit);
123 |
124 | // установить deadtime (в микросекундах). По умолч 0
125 | void setDeadtime(uint16_t deadtime);
126 |
127 | // установить уровень драйвера (по умолч. HIGH)
128 | void setLevel(int8_t level);
129 |
130 | // плавное изменение к указанной скорости (к значению ШИМ)
131 | void smoothTick(int16_t duty);
132 |
133 | // скорость изменения скорости
134 | void setSmoothSpeed(uint8_t speed);
135 |
136 | // возвращает -1 при вращении BACKWARD, 1 при FORWARD и 0 при остановке и торможении
137 | int getState();
138 |
139 | // внутренняя переменная скважности для отладки
140 | int16_t _duty = 0;
141 |
142 | // свовместимость со старыми версиями
143 | // установить выход в 8 бит
144 | void set8bitMode();
145 |
146 | // установить выход в 10 бит
147 | void set10bitMode();
148 | ```
149 |
150 | ### Логика работы
151 | В setMinDuty() можно установить минимальную скорость (0..255), при которой мотор начинает вращение.
152 | Дальнейшие настройки скорости будут автоматически масштабироваться с учётом минимальной.
153 | setDirection() задаёт глобальное направление мотора, которое автоматически влияет на все функции скорости.
154 |
155 | #### Обычный режим
156 | Запускается setMode(FORWARD) для движения вперёд, setMode(BACKWARD) - назад.
157 | Скорость устанавливается в setSpeed() либо run(FORWARD/BACKWARD, скорость). Остановить можно setMode(STOP).
158 |
159 | #### Авто режим
160 | Запускается setMode(AUTO), скорость задаётся в setSpeed(), поддерживаются отрицательные значения для вращения в другую сторону.
161 | Остановить можно setMode(STOP).
162 |
163 | #### Плавный режим
164 | Для запуска нужно установить setMode(AUTO). В плавном режиме нужно почаще вызывать smoothTick с указанием целевой скорости. При значении 0 мотор сам плавно остановится.
165 | Для резкой остановки можно использовать setMode(STOP).
166 |
167 |
168 |
169 |
170 | GyverMotor2
171 |
172 | ```cpp
173 | void setMinDuty(uint16_t mduty); // установить минимальный ШИМ (умолч. 0)
174 | void setMinDutyPerc(uint16_t mduty); // установить минимальный ШИМ в % (умолч. 0)
175 | void setDeadtime(uint16_t us); // установить deadtime в микросекундах (умолч. 0)
176 | void reverse(bool r); // реверс направления (умолч. false)
177 |
178 | void stop(); // остановка. Если включен плавный режим, то плавная
179 | void brake(); // активный тормоз
180 | void setSpeed(int16_t s); // установить скорость (-макс.. макс)
181 | void setSpeedPerc(int16_t s); // установить скорость в процентах (-100.. 100%)
182 |
183 | int8_t getState(); // получить статус: мотор крутится (1 и -1), мотор остановлен (0)
184 | int16_t getSpeed(); // получить текущую скорость мотора
185 |
186 | void smoothMode(bool mode); // установить режим плавного изменения скорости (умолч. false)
187 | void tick(); // плавное изменение к указанной скорости, вызывать в цикле
188 | void setSmoothSpeed(uint8_t s); // установить скорость изменения скорости (умолч. 20)
189 | void setSmoothSpeedPerc(uint8_t s); // установить скорость изменения скорости в процентах
190 | ```
191 |
192 | ### Разрядность ШИМ
193 | В AVR Arduino по умолчанию используется 8-ми битный ШИМ (0.. 255). В esp8266 используется 10-ти битный (0.. 1023).
194 | При инициализации библиотеки можно настроить нужную разрядность, она может быть любой.
195 |
196 | ### Скорость
197 | Скорость задаётся в `setSpeed(-макс ШИМ.. макс ШИМ)` в величине ШИМ сигнала, либо в `setSpeedPerc(-100.. 100)` в процентах. Скорость может быть отрицательной,
198 | тогда мотор будет крутиться в обратную сторону. При значении 0 мотор остановится и драйвер будет отключен.
199 |
200 | ### Режимы работы
201 | Вызов `stop()` равносилен `setSpeed(0)`. При прямом управлении мотор будет сразу остановлен, при плавном - остановится плавно. Драйвер отключится, вал мотора будет освобождён.
202 | Вызов `brake()` остановит мотор и переключит драйвер в режим активного торможения (замкнёт мотор через себя). Вал мотора будет сопротивляться вращению.
203 | Вызов `reverse(true)` инвертирует направление вращения мотора для всех функций.
204 |
205 | ### Минимальный ШИМ
206 | В `setMinDuty(-макс ШИМ.. макс ШИМ)` можно установить минимальную скорость, при которой мотор начинает вращение, это удобно в большинстве применений.
207 | Установленная в `setSpeed()` скорость будет автоматически масштабироваться с учётом минимальной.
208 | Также можно задать минимальную скорость в процентах `setMinDutyPerc(-100.. 100)`.
209 |
210 | ### Плавный режим
211 | В плавном режиме установленная в `setSpeed()` скорость применяется не сразу, а плавно в течением времени. Для включения
212 | плавного режима нужно вызвать `smoothMode(true)` и поместить в основном цикле программы функцию-тикер `tick()`.
213 | Внутри этой функции скорсть будет плавно меняться по встроенному таймеру (период - 50мс).
214 | Можно настроить скорость изменения скорости - `setSmoothSpeed()` в величинах ШИМ и `setSmoothSpeedPerc()` в процентах.
215 |
216 |
217 |
218 | ## Пример
219 | Остальные примеры смотри в **examples**!
220 | ```cpp
221 | #include
222 | GMotor2 motor(5, 6);
223 | //GMotor2 motor(5, 6);
224 | //GMotor2 motor(5, 6);
225 | //GMotor2 motor(5, 6, 11);
226 | //GMotor2 motor(5, 6);
227 |
228 | void setup() {
229 | motor.setMinDuty(70); // мин. ШИМ
230 | //motor.reverse(1); // реверс
231 | //motor.setDeadtime(5); // deadtime
232 | }
233 |
234 | void loop() {
235 | motor.setSpeed(10);
236 | delay(1000);
237 | motor.setSpeed(-100);
238 | delay(1000);
239 | motor.setSpeed(50);
240 | delay(1000);
241 | motor.setSpeed(255);
242 | delay(1000);
243 | motor.brake();
244 | delay(3000);
245 | }
246 | ```
247 |
248 |
249 | ## Версии
250 | - v1.1 - убраны дефайны
251 | - v1.2 - возвращены дефайны
252 | - v2.0:
253 | - Программный deadtime
254 | - Отрицательные скорости
255 | - Поддержка двух типов драйверов и реле
256 | - Плавный пуск и изменение скорости
257 | - v2.1: небольшие фиксы и добавления
258 | - v2.2: оптимизация
259 | - v2.3: добавлена поддержка esp (исправлены ошибки)
260 | - v2.4: совместимость с другими библами
261 | - v2.5: добавлен тип DRIVER2WIRE_NO_INVERT
262 | - v3.0: переделана логика minDuty, добавлен режим для ШИМ любой битности
263 | - v3.1: мелкие исправления
264 | - v3.2: улучшена стабильность плавного режима
265 | - v3.2.1: вернул run() в public
266 | - v4.0: исправлен баг в GyverMotor. Добавлен GyverMotor2
267 |
268 |
269 | ## Баги и обратная связь
270 | При нахождении багов создавайте **Issue**, а лучше сразу пишите на почту [alex@alexgyver.ru](mailto:alex@alexgyver.ru)
271 | Библиотека открыта для доработки и ваших **Pull Request**'ов!
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor/motor_control_10bit/motor_control_10bit.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Пример управления мотором при помощи драйвера полного моста и потенциометра
3 | на ШИМ 10 бит
4 | */
5 |
6 | #include "GyverMotor.h"
7 | GMotor motor(DRIVER2WIRE, 2, 9, HIGH);
8 |
9 | // варианты инициализации в зависимости от типа драйвера:
10 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) )
11 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
12 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
13 | /*
14 | DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
15 | DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
16 | RELAY2WIRE - реле в качестве драйвера (два пина направления)
17 |
18 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
19 | PWM_pin - любой ШИМ пин МК
20 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
21 | */
22 |
23 | void setup() {
24 | // разгоняем ШИМ на пинах 9 и 10 (atmega328) до 16 кГц 10 бит
25 | // читай тут: https://alexgyver.ru/lessons/pwm-overclock/
26 | TCCR1A = 0b00000011; // 10bit
27 | TCCR1B = 0b00001001; // x1 fast pwm
28 |
29 | // активируем 10-битный режим библиотеки
30 | motor.setResolution(10);
31 |
32 | // ключ на старт!
33 | motor.setMode(FORWARD);
34 | }
35 |
36 | void loop() {
37 | // потенциометр на А0
38 | // преобразуем значение в -1023.. 1023
39 | int val = 1023 - analogRead(0) * 2;
40 |
41 | motor.setSpeed(val);
42 | // в данном случае мотор будет остановлен в среднем положении рукоятки
43 | // и разгоняться в противоположные скорости в крайних её положениях
44 |
45 | delay(10); // задержка просто для "стабильности"
46 | }
47 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor/motor_control_31kHz/motor_control_31kHz.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Пример управления мотором при помощи драйвера полного моста и потенциометра
3 | на разогнанном ШИМе
4 | */
5 |
6 | #include "GyverMotor.h"
7 | GMotor motor(DRIVER2WIRE, 2, 3, HIGH);
8 |
9 | // варианты инициализации в зависимости от типа драйвера:
10 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) )
11 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
12 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
13 | /*
14 | DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
15 | DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
16 | RELAY2WIRE - реле в качестве драйвера (два пина направления)
17 |
18 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
19 | PWM_pin - любой ШИМ пин МК
20 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
21 | */
22 |
23 | void setup() {
24 | // разгоняем ШИМ на пинах 3 и 11 (atmega328) до 31 кГц
25 | // читай тут: https://alexgyver.ru/lessons/pwm-overclock/
26 | TCCR2B = 0b00000001; // x1
27 | TCCR2A = 0b00000001; // phase correct
28 |
29 | // ключ на старт!
30 | motor.setMode(FORWARD);
31 | }
32 |
33 | void loop() {
34 | // потенциометр на А0
35 | // преобразуем значение в -255.. 255
36 | int val = 255 - analogRead(0) / 2;
37 |
38 | motor.setSpeed(val);
39 | // в данном случае мотор будет остановлен в среднем положении рукоятки
40 | // и разгоняться в противоположные скорости в крайних её положениях
41 |
42 | delay(10); // задержка просто для "стабильности"
43 | }
44 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor/motor_demo/motor_demo.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Пример управления мотором при помощи драйвера полного моста и потенциометра
3 | */
4 | #include "GyverMotor.h"
5 | GMotor motor(DRIVER2WIRE, 2, 3, HIGH);
6 |
7 | // варианты инициализации в зависимости от типа драйвера:
8 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) )
9 | // GMotor motor(DRIVER2WIRE_NO_INVERT, dig_pin, PWM_pin, (LOW / HIGH) )
10 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
11 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
12 | /*
13 | DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
14 | DRIVER2WIRE_NO_INVERT - двухпроводной драйвер, в котором при смене направления не нужна инверсия ШИМ
15 | DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
16 | RELAY2WIRE - реле в качестве драйвера (два пина направления)
17 |
18 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
19 | PWM_pin - любой ШИМ пин МК
20 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
21 | */
22 |
23 | void setup() {
24 | // установка программного deadtime на переключение направления, микросекунды
25 | // по умолчанию стоит 0: deadtime отключен
26 | // motor.setDeadtime(200);
27 |
28 | // ГЛОБАЛЬНАЯ смена направления вращения мотора
29 | // например чтобы FORWARD совпадал с направлением движения "вперёд" у машинки
30 | motor.setDirection(REVERSE);
31 | motor.setDirection(NORMAL); // умолч.
32 |
33 | // смена режима работы мотора
34 | motor.setMode(FORWARD); // вперёд
35 | motor.setMode(BACKWARD); // назад
36 | motor.setMode(BRAKE); // активный тормоз
37 | motor.setMode(STOP); // стоп, холостой (мотор отключен)
38 |
39 | // смена уровня драйвера (аналогично при инициализации)
40 | // Если при увеличении скорости мотор наоборот тормозит - смени уровень
41 | motor.setLevel(LOW);
42 | motor.setLevel(HIGH); // по умолч.
43 |
44 |
45 | // для работы в 10 бит необходимо также настроить ШИМ на 10 бит!!!
46 | // читай тут https://alexgyver.ru/lessons/pwm-overclock/
47 | // motor.setResolution(10);
48 |
49 | // минимальный сигнал (по модулю), который будет подан на мотор
50 | // Избавляет от ситуаций, когда мотор покоится и "пищит"
51 | motor.setMinDuty(150);
52 |
53 | // ключ на старт!
54 | motor.setMode(FORWARD);
55 | }
56 |
57 | void loop() {
58 | // потенциометр на А0
59 | // преобразуем значение в -255.. 255
60 | int val = 255 - analogRead(0) / 2;
61 |
62 | // установка скорости:
63 | // * (0..255) при ручном выборе направления (setMode: FORWARD/BACKWARD)
64 | // * (-255..255) при автоматическом (поставить setMode(FORWARD))
65 | // * (0..1023) в режиме 10 бит при ручном выборе направления (setMode: FORWARD/BACKWARD)
66 | // * (-1023..1023) в режиме 10 бит при автоматическом (поставить setMode(FORWARD))
67 |
68 | motor.setSpeed(val);
69 | // в данном случае мотор будет остановлен в среднем положении рукоятки
70 | // и разгоняться в противоположные скорости в крайних её положениях
71 |
72 | delay(10); // задержка просто для "стабильности"
73 | }
74 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor/multi_motor/multi_motor.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Пример управления двумя моторами
3 | */
4 | #include "GyverMotor.h"
5 | GMotor motor1(DRIVER2WIRE, 2, 3, HIGH);
6 | GMotor motor2(DRIVER2WIRE, 4, 11, HIGH);
7 | // используем оба ШИМа таймера 2 (пины 3 и 11)
8 |
9 | // варианты инициализации в зависимости от типа драйвера:
10 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) )
11 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
12 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
13 | /*
14 | DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
15 | DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
16 | RELAY2WIRE - реле в качестве драйвера (два пина направления)
17 |
18 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
19 | PWM_pin - любой ШИМ пин МК
20 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
21 | */
22 |
23 | void setup() {
24 | // ключ на старт!
25 | motor1.setMode(FORWARD);
26 | motor2.setMode(FORWARD);
27 | }
28 |
29 | void loop() {
30 | // потенциометр на А0
31 | // преобразуем значение в -255.. 255
32 | int val_1 = 255 - analogRead(0) / 2;
33 |
34 | // потенциометр на А1
35 | // преобразуем значение в -255.. 255
36 | int val_2 = 255 - analogRead(1) / 2;
37 |
38 | motor1.setSpeed(val_1);
39 | motor2.setSpeed(val_2);
40 | // в данном случае мотор будет остановлен в среднем положении рукоятки
41 | // и разгоняться в противоположные скорости в крайних её положениях
42 |
43 | delay(10); // задержка просто для "стабильности"
44 | }
45 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor/multi_motor_tank/multi_motor_tank.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Пример управления двумя моторами при помощи одного джойстика по танковой схеме
3 | */
4 | #include "GyverMotor.h"
5 | GMotor motorR(DRIVER2WIRE, 2, 3, HIGH);
6 | GMotor motorL(DRIVER2WIRE, 4, 11, HIGH);
7 | // используем оба ШИМа таймера 2 (пины 3 и 11)
8 |
9 | // варианты инициализации в зависимости от типа драйвера:
10 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) )
11 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
12 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
13 | /*
14 | DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
15 | DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
16 | RELAY2WIRE - реле в качестве драйвера (два пина направления)
17 |
18 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
19 | PWM_pin - любой ШИМ пин МК
20 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
21 | */
22 |
23 | void setup() {
24 | // ключ на старт!
25 | motorR.setMode(FORWARD);
26 | motorL.setMode(FORWARD);
27 | }
28 |
29 | void loop() {
30 | // джойстик на А0 и А1
31 | int signalX = 255 - analogRead(0) / 2;
32 | int signalY = 255 - analogRead(1) / 2;
33 |
34 | // преобразуем по танковой схеме
35 | int dutyR = signalY + signalX;
36 | int dutyL = signalY - signalX;
37 |
38 | motorR.setSpeed(dutyR);
39 | motorL.setSpeed(dutyL);
40 |
41 | delay(10); // задержка просто для "стабильности"
42 | }
43 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor/smooth_control/smooth_control.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Пример плавного управления мотором при помощи драйвера полного моста и потенциометра
3 | */
4 | #include "GyverMotor.h"
5 | GMotor motor(DRIVER2WIRE, 2, 3, HIGH);
6 |
7 | // варианты инициализации в зависимости от типа драйвера:
8 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW / HIGH) )
9 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
10 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
11 | /*
12 | DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
13 | DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
14 | RELAY2WIRE - реле в качестве драйвера (два пина направления)
15 |
16 | dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
17 | PWM_pin - любой ШИМ пин МК
18 | LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
19 | */
20 |
21 | void setup() {
22 | Serial.begin(9600);
23 |
24 | // установка скорости изменения скорости (ускорения) мотора
25 | motor.setSmoothSpeed(20);
26 |
27 | // ключ на старт!
28 | motor.setMode(FORWARD);
29 | }
30 |
31 | void loop() {
32 | // потенциометр на А0
33 | // преобразуем значение в -255.. 255
34 | int val = 255 - analogRead(0) / 2;
35 |
36 | // данную функцию рекомендуется вызывать чаще чем каждые 50 мс
37 | // (работает по встроенному таймеру)
38 | // она будет плавно менять скорость мотора к заданной
39 | motor.smoothTick(val);
40 |
41 | // отладка. Откройте Инструменты/Плоттер по последовательному порту
42 | Serial.print(val); // первый график - установленная скорость
43 | Serial.print(',');
44 | Serial.println(motor._duty); // второй график - реальный сигнал на мотор
45 |
46 | delay(10); // задержка просто для "стабильности"
47 | }
48 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor2/demo/demo.ino:
--------------------------------------------------------------------------------
1 | #include
2 | GMotor2 motor(5, 6);
3 | //GMotor2 motor(5, 6);
4 | //GMotor2 motor(5, 6);
5 | //GMotor2 motor(5, 6, 11);
6 | //GMotor2 motor(5, 6);
7 |
8 | void setup() {
9 | motor.setMinDuty(70); // мин. ШИМ
10 | //motor.reverse(1); // реверс
11 | //motor.setDeadtime(5); // deadtime
12 | }
13 |
14 | void loop() {
15 | motor.setSpeed(10);
16 | delay(1000);
17 | motor.setSpeed(-100);
18 | delay(1000);
19 | motor.setSpeed(50);
20 | delay(1000);
21 | motor.setSpeed(255);
22 | delay(1000);
23 | motor.brake();
24 | delay(3000);
25 | }
26 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor2/potControl/potControl.ino:
--------------------------------------------------------------------------------
1 | // потенциометр на A0
2 |
3 | #include
4 | GMotor2 motor(5, 6);
5 |
6 | void setup() {
7 | motor.setMinDuty(70); // мин. ШИМ
8 | //motor.reverse(1); // реверс
9 | //motor.setDeadtime(5); // deadtime
10 | }
11 |
12 | void loop() {
13 | // переводим в диапазон -255.. 255
14 | int val = analogRead(0) / 2 - 512;
15 | motor.setSpeed(val);
16 | delay(100);
17 | }
18 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/examples/GyverMotor2/serialControl/serialControl.ino:
--------------------------------------------------------------------------------
1 | // открой плоттер на скорости 9600. Команды:
2 | // q<скорость> - скорость в процентах (пример: q0, q50, q90)
3 | // w - stop()
4 | // e - brake()
5 |
6 | #include
7 | GMotor2 motor(5, 6);
8 |
9 | void setup() {
10 | Serial.begin(9600);
11 | Serial.setTimeout(40);
12 | motor.setMinDuty(70); // мин. ШИМ
13 | //motor.reverse(1); // реверс
14 | //motor.setDeadtime(5); // deadtime
15 | motor.smoothMode(1); // плавный режим
16 | }
17 |
18 | void loop() {
19 | motor.tick();
20 |
21 | // вывод графика
22 | static uint32_t tmr;
23 | if (millis() - tmr > 50) {
24 | tmr = millis();
25 | Serial.println(motor.getSpeed());
26 | }
27 |
28 | if (Serial.available() > 0) {
29 | char key = Serial.read();
30 | int val = Serial.parseInt();
31 | switch (key) {
32 | case 'q': motor.setSpeedPerc(val); break;
33 | case 'w': motor.stop(); break;
34 | case 'e': motor.brake(); break;
35 | }
36 | }
37 | }
38 |
--------------------------------------------------------------------------------
/libraries/GyverMotor/keywords.txt:
--------------------------------------------------------------------------------
1 | #######################################
2 | # Syntax Coloring Map For GyverMotor
3 | #######################################
4 |
5 | #######################################
6 | # Datatypes (KEYWORD1)
7 | #######################################
8 | GMotor KEYWORD1
9 | GyverMotor KEYWORD1
10 | GMotor2 KEYWORD1
11 | GyverMotor2 KEYWORD1
12 |
13 | #######################################
14 | # Methods and Functions (KEYWORD2)
15 | #######################################
16 | setSpeed KEYWORD2
17 | setMode KEYWORD2
18 | setDirection KEYWORD2
19 | setResolution KEYWORD2
20 | setDeadtime KEYWORD2
21 | setLevel KEYWORD2
22 | setMinDuty KEYWORD2
23 | getState KEYWORD2
24 | run KEYWORD2
25 |
26 | smoothTick KEYWORD2
27 | setSmoothSpeed KEYWORD2
28 |
29 | set8bitMode KEYWORD2
30 | set10bitMode KEYWORD2
31 |
32 | reverse KEYWORD2
33 | stop KEYWORD2
34 | brake KEYWORD2
35 | tick KEYWORD2
36 | smoothMode KEYWORD2
37 | getSpeed KEYWORD2
38 | setSpeedPerc KEYWORD2
39 | setMinDutyPerc KEYWORD2
40 | setSmoothSpeedPerc KEYWORD2
41 |
42 | #######################################
43 | # Constants (LITERAL1)
44 | #######################################
45 | DRIVER2WIRE_NO_INVERT LITERAL1
46 | DRIVER2WIRE_PWM LITERAL1
47 | DRIVER2WIRE LITERAL1
48 | DRIVER3WIRE LITERAL1
49 | RELAY2WIRE LITERAL1
50 |
51 | NORMAL LITERAL1
52 | REVERSE LITERAL1
53 |
54 | FORWARD LITERAL1
55 | BACKWARD LITERAL1
56 | STOP LITERAL1
57 | BRAKE LITERAL1
58 | AUTO LITERAL1
--------------------------------------------------------------------------------
/libraries/GyverMotor/library.properties:
--------------------------------------------------------------------------------
1 | name=GyverMotor
2 | version=4.0
3 | author=AlexGyver
4 | maintainer=AlexGyver
5 | sentence=Library for motor driver control
6 | paragraph=Library for motor driver control
7 | category=Device Control
8 | url=https://github.com/GyverLibs/GyverMotor
9 | architectures=*
--------------------------------------------------------------------------------
/libraries/GyverMotor/src/GyverMotor.cpp:
--------------------------------------------------------------------------------
1 | #include "GyverMotor.h"
2 |
3 | GMotor::GMotor(GM_driverType type, int8_t param1, int8_t param2, int8_t param3, int8_t param4) {
4 | _type = type;
5 | switch (_type) {
6 | case DRIVER2WIRE_NO_INVERT:
7 | case DRIVER2WIRE:
8 | _digA = param1;
9 | _pwmC = param2;
10 | if (param3 != _GM_NC) _level = !param3;
11 | break;
12 | case DRIVER3WIRE:
13 | _digA = param1;
14 | _digB = param2;
15 | _pwmC = param3;
16 | if (param4 != _GM_NC) _level = !param4;
17 | break;
18 | case RELAY2WIRE:
19 | _digA = param1;
20 | _digB = param2;
21 | if (param3 != _GM_NC) _level = !param3;
22 | break;
23 | }
24 |
25 | if (_digA != _GM_NC) pinMode(_digA, OUTPUT);
26 | if (_digB != _GM_NC) pinMode(_digB, OUTPUT);
27 | if (_pwmC != _GM_NC) pinMode(_pwmC, OUTPUT);
28 |
29 | setMode(STOP);
30 | }
31 |
32 | void GMotor::setSpeed(int16_t duty) {
33 | if (_mode < 2) { // FORWARD/BACKWARD/AUTO
34 | _duty = constrain(duty, -_maxDuty, _maxDuty);
35 |
36 | // фикс стандартного analogWrite(пин, 255) для >8 бит
37 | if (_maxDuty > 255 && abs(_duty) == 255) _duty++;
38 |
39 | if (duty == 0) run(STOP, 0);
40 | else {
41 | if (duty > 0) {
42 | if (_minDuty != 0) _duty = _duty * _k + _minDuty; // сжимаем диапазон
43 | run(_mode, _duty);
44 | } else {
45 | if (_minDuty != 0) _duty = _duty * _k - _minDuty; // сжимаем диапазон
46 | run(BACKWARD, -_duty);
47 | }
48 | }
49 | }
50 | }
51 |
52 | void GMotor::run(GM_workMode mode, int16_t duty) {
53 | // дедтайм
54 | if (_deadtime > 0 && _lastMode != mode) {
55 | _lastMode = mode;
56 | setPins(_level, _level, 0); // выключить всё
57 | delayMicroseconds(_deadtime);
58 | }
59 |
60 | // инверт
61 | if (_direction) {
62 | if (mode == FORWARD) mode = BACKWARD;
63 | else if (mode == BACKWARD) mode = FORWARD;
64 | }
65 |
66 | switch (mode) {
67 | case FORWARD: setPins(_level, !_level, duty); _state = 1; break;
68 | case BACKWARD: setPins(!_level, _level, (_type == DRIVER2WIRE) ? (_maxDuty - duty) : (duty)); _state = -1; break;
69 | case BRAKE: setPins(!_level, !_level, !_level * 255); _state = 0; break; // при 0/255 analogWrite сделает 0/1
70 | case STOP: setPins(_level, _level, _level * 255); _duty = _dutyS = 0; _state = 0; break;
71 | }
72 | }
73 |
74 | void GMotor::setPins(bool a, bool b, int c) {
75 | if (_digA != _GM_NC) digitalWrite(_digA, a);
76 | if (_digB != _GM_NC) digitalWrite(_digB, b);
77 | if (_pwmC != _GM_NC) analogWrite(_pwmC, c);
78 | }
79 |
80 | void GMotor::smoothTick(int16_t duty) {
81 | if (millis() - _tmr >= _SMOOTH_PRD) {
82 | _tmr = millis();
83 | if (abs(_dutyS - duty) > _speed) _dutyS += (_dutyS < duty) ? _speed : -_speed;
84 | else _dutyS = duty;
85 | setSpeed(_dutyS);
86 | }
87 | }
88 |
89 | int GMotor::getState() {
90 | return _state;
91 | }
92 |
93 | void GMotor::setResolution(byte bit) {
94 | _maxDuty = (1 << bit) - 1; // -1 для смещения
95 | setMinDuty(_minDuty); // пересчитаем k
96 | }
97 |
98 | void GMotor::setMinDuty(int duty) {
99 | _minDuty = duty;
100 | _k = 1.0 - (float)_minDuty / _maxDuty;
101 | }
102 |
103 | void GMotor::setMode(GM_workMode mode) {
104 | if (_mode == mode) return;
105 | _mode = mode;
106 | run(mode, _duty);
107 | }
108 |
109 | void GMotor::setSmoothSpeed(uint8_t speed) {
110 | _speed = speed;
111 | }
112 |
113 | void GMotor::setDirection(bool direction) {
114 | _direction = direction;
115 | }
116 |
117 | void GMotor::setDeadtime(uint16_t deadtime) {
118 | _deadtime = deadtime;
119 | }
120 |
121 | void GMotor::setLevel(int8_t level) {
122 | _level = !level;
123 | }
124 |
125 | // совместимость
126 | void GMotor::set8bitMode() {
127 | setResolution(8);
128 | }
129 |
130 | void GMotor::set10bitMode() {
131 | setResolution(10);
132 | }
--------------------------------------------------------------------------------
/libraries/GyverMotor/src/GyverMotor.h:
--------------------------------------------------------------------------------
1 | /*
2 | Библиотека для удобного управления коллекторными моторами через драйвер
3 | Документация: https://alexgyver.ru/gyvermotor/
4 | GitHub: https://github.com/GyverLibs/GyverMotor
5 | Возможности:
6 | - Контроль скорости и направления вращения
7 | - Работа с ШИМ любого разрешения
8 | - Плавный пуск и изменение скорости
9 | - Активный тормоз
10 | - Порог минимального ШИМ
11 | - Deadtime
12 | - Поддержка 5 типов драйверов
13 |
14 | AlexGyver, alex@alexgyver.ru
15 | https://alexgyver.ru/
16 | MIT License
17 |
18 | Версии:
19 | v1.1 - убраны дефайны
20 | v1.2 - возвращены дефайны
21 | v2.0:
22 | - Программный deadtime
23 | - Отрицательные скорости
24 | - Поддержка двух типов драйверов и реле
25 | - Плавный пуск и изменение скорости
26 | v2.1: небольшие фиксы и добавления
27 | v2.2: оптимизация
28 | v2.3: добавлена поддержка esp (исправлены ошибки)
29 | v2.4: совместимость с другими библами
30 | v2.5: добавлен тип DRIVER2WIRE_NO_INVERT
31 | v3.0: переделана логика minDuty, добавлен режим для ШИМ любой битности
32 | v3.1: мелкие исправления
33 | v3.2: улучшена стабильность плавного режима
34 | v3.2.1: вернул run() в public
35 | v4.0: исправлен баг в GyverMotor. Добавлен GyverMotor2
36 | */
37 |
38 | #ifndef _GyverMotor_h
39 | #define _GyverMotor_h
40 | #include
41 | #define _SMOOTH_PRD 50 // таймер smoothTick, мс
42 |
43 | enum GM_driverType {
44 | DRIVER2WIRE_NO_INVERT, // двухпроводной драйвер, в котором при смене направления не нужна инверсия ШИМ
45 | DRIVER2WIRE, // двухпроводной драйвер (направление + ШИМ)
46 | DRIVER3WIRE, // трёхпроводной драйвер (два пина направления + ШИМ)
47 | RELAY2WIRE, // реле в качестве драйвера (два пина направления)
48 | };
49 |
50 | #define NORMAL 0
51 | #define REVERSE 1
52 |
53 | enum GM_workMode {
54 | FORWARD,
55 | BACKWARD,
56 | STOP,
57 | BRAKE,
58 | AUTO = 0,
59 | };
60 |
61 | static const int8_t _GM_NC = -1; // not connected
62 |
63 | class GMotor {
64 | public:
65 | GMotor(GM_driverType type, int8_t param1 = _GM_NC, int8_t param2 = _GM_NC, int8_t param3 = _GM_NC, int8_t param4 = _GM_NC);
66 | // три варианта создания объекта в зависимости от драйвера:
67 | // GMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, (LOW/HIGH) )
68 | // GMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, (LOW/HIGH) )
69 | // GMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, (LOW/HIGH) )
70 |
71 | // установка скорости -255..255 (8 бит) и -1023..1023 (10 бит)
72 | void setSpeed(int16_t duty);
73 |
74 | // сменить режим работы мотора:
75 | // FORWARD - вперёд
76 | // BACKWARD - назад
77 | // STOP - остановить
78 | // BRAKE - активный тормоз
79 | // AUTO - подчиняется setSpeed (-255.. 255)
80 | void setMode(GM_workMode mode);
81 |
82 | // направление вращения
83 | // NORM - обычное
84 | // REVERSE - обратное
85 | void setDirection(bool direction);
86 |
87 | // дать прямую команду мотору (без смены режима)
88 | void run(GM_workMode mode, int16_t duty = 0);
89 |
90 | // установить минимальную скважность (при которой мотор начинает крутиться)
91 | void setMinDuty(int duty);
92 |
93 | // установить разрешение ШИМ в битах
94 | void setResolution(byte bit);
95 |
96 | // установить deadtime (в микросекундах). По умолч 0
97 | void setDeadtime(uint16_t deadtime);
98 |
99 | // установить уровень драйвера (по умолч. HIGH)
100 | void setLevel(int8_t level);
101 |
102 | // плавное изменение к указанной скорости (к значению ШИМ)
103 | void smoothTick(int16_t duty);
104 |
105 | // скорость изменения скорости
106 | void setSmoothSpeed(uint8_t speed);
107 |
108 | // возвращает -1 при вращении BACKWARD, 1 при FORWARD и 0 при остановке и торможении
109 | int getState();
110 |
111 | // внутренняя переменная скважности для отладки
112 | int16_t _duty = 0;
113 |
114 | // свовместимость со старыми версиями
115 | // установить выход в 8 бит
116 | void set8bitMode();
117 |
118 | // установить выход в 10 бит
119 | void set10bitMode();
120 |
121 | protected:
122 | void setPins(bool a, bool b, int c);
123 | int16_t _dutyS = 0;
124 | int _minDuty = 0, _state = 0;;
125 | int8_t _digA = _GM_NC, _digB = _GM_NC, _pwmC = _GM_NC;
126 | bool _direction = false;
127 | int8_t _level = LOW; // логика инвертирована!
128 | int _maxDuty = 255;
129 | GM_workMode _mode = FORWARD, _lastMode = FORWARD;
130 | GM_driverType _type;
131 | uint16_t _deadtime = 0;
132 | uint8_t _speed = 20;
133 | uint32_t _tmr = 0;
134 | float _k;
135 | };
136 | #endif
--------------------------------------------------------------------------------
/libraries/GyverMotor/src/GyverMotor2.h:
--------------------------------------------------------------------------------
1 | #ifndef _GyverMotor2_h
2 | #define _GyverMotor2_h
3 | #include
4 |
5 | enum GM_driver {
6 | DRIVER2WIRE, // двухпроводной драйвер с инверсией шим (dir + PWM)
7 | DRIVER2WIRE_NO_INVERT, // двухпроводной драйвер без инверсии ШИМ (dir + PWM)
8 | DRIVER2WIRE_PWM, // двухпроводной драйвер с двумя ШИМ (PWM + PWM)
9 | DRIVER3WIRE, // трёхпроводной драйвер (dir + dir + PWM)
10 | RELAY2WIRE, // реле в качестве драйвера (dir + dir)
11 | };
12 |
13 | #define _GM_SMOOTH_PRD 50 // период таймера плавной скорости, мс
14 |
15 | template
16 | class GMotor2 {
17 | public:
18 | // инициализация с указанием пинов
19 | GMotor2(uint8_t pa, uint8_t pb, uint8_t pc = 255) : pinA(pa), pinB(pb), pinC(pc) {
20 | pinMode(pinA, OUTPUT);
21 | pinMode(pinB, OUTPUT);
22 | if (pinC != 255) pinMode(pinC, OUTPUT);
23 | setAll(0);
24 | }
25 |
26 | // установить минимальный ШИМ (умолч. 0)
27 | void setMinDuty(uint16_t mduty) {
28 | minD = mduty;
29 | }
30 |
31 | // установить минимальный ШИМ в % (умолч. 0)
32 | void setMinDutyPerc(uint16_t mduty) {
33 | mduty = constrain(mduty, 0, 100);
34 | minD = (int32_t)getMax() * mduty / 100;
35 | }
36 |
37 | // реверс направления (умолч. false)
38 | void reverse(bool r) {
39 | rev = r ? -1 : 1;
40 | }
41 |
42 | // остановка. Если включен плавный режим, то плавная
43 | void stop() {
44 | setSpeed(0);
45 | }
46 |
47 | // активный тормоз
48 | void brake() {
49 | setAll(1);
50 | speed = duty = 0;
51 | }
52 |
53 | // установить скорость (-макс.. макс)
54 | void setSpeed(int16_t s) {
55 | speed = s;
56 | if (!smooth) duty = speed;
57 | run(duty);
58 | }
59 |
60 | // установить скорость в процентах (-100.. 100%)
61 | void setSpeedPerc(int16_t s) {
62 | s = constrain(s, -100, 100);
63 | setSpeed((int32_t)getMax() * s / 100);
64 | }
65 |
66 | // установить deadtime в микросекундах (умолч. 0)
67 | void setDeadtime(uint16_t us) {
68 | dead = us;
69 | }
70 |
71 | // плавное изменение к указанной скорости, вызывать в цикле
72 | void tick() {
73 | if ((speed || duty) && smooth && millis() - tmr >= _GM_SMOOTH_PRD) {
74 | tmr = millis();
75 | if (abs(duty - speed) > ds) duty += (duty < speed) ? ds : -ds;
76 | else duty = speed;
77 | run(duty);
78 | }
79 | }
80 |
81 | // установить скорость изменения скорости (умолч. 20)
82 | void setSmoothSpeed(uint8_t s) {
83 | ds = s;
84 | }
85 |
86 | // установить скорость изменения скорости в процентах
87 | void setSmoothSpeedPerc(uint8_t s) {
88 | s = constrain(s, 0, 100);
89 | ds = (int32_t)getMax() * s / 100;
90 | }
91 |
92 | // установить режим плавного изменения скорости (умолч. false)
93 | void smoothMode(bool mode) {
94 | smooth = mode;
95 | }
96 |
97 | // получить статус: мотор крутится (1 и -1), мотор остановлен (0)
98 | int8_t getState() {
99 | return dir;
100 | }
101 |
102 | // получить текущую скорость мотора
103 | int16_t getSpeed() {
104 | return duty;
105 | }
106 |
107 | private:
108 | // макс ШИМ при разрешении
109 | int16_t getMax() {
110 | return (1 << GM_RES) - 1;
111 | }
112 |
113 | // установка скорости -макс.. макс
114 | void run(int16_t sp) {
115 | if (!sp) return setAll(0); // стоп
116 | int8_t ndir = (sp > 0) ? rev : -rev;
117 | if (dead && ndir != dir) { // направление изменилось
118 | setAll(0);
119 | delayMicroseconds(dead);
120 | }
121 | dir = ndir;
122 | int16_t maxD = getMax();
123 | sp = constrain(sp, -maxD, maxD);
124 | if (minD) sp = (int32_t)sp * (maxD - minD) >> GM_RES;
125 | sp = abs(sp) + minD;
126 | if (GM_RES > 8 && sp == 255) sp++; // защита от 255 при разрешении > 8 бит
127 |
128 | switch (GM_TYPE) {
129 | case DRIVER2WIRE:
130 | digitalWrite(pinA, dir < 0);
131 | analogWrite(pinB, (dir > 0) ? sp : (maxD - sp));
132 | break;
133 |
134 | case DRIVER2WIRE_NO_INVERT:
135 | digitalWrite(pinA, dir < 0);
136 | analogWrite(pinB, sp);
137 | break;
138 |
139 | case DRIVER2WIRE_PWM:
140 | if (dir > 0) {
141 | digitalWrite(pinA, 0);
142 | analogWrite(pinB, sp);
143 | } else {
144 | analogWrite(pinA, sp);
145 | digitalWrite(pinB, 0);
146 | }
147 | break;
148 |
149 | case DRIVER3WIRE:
150 | digitalWrite(pinA, dir < 0);
151 | digitalWrite(pinB, dir > 0);
152 | analogWrite(pinC, sp);
153 | break;
154 |
155 | case RELAY2WIRE:
156 | digitalWrite(pinA, dir < 0);
157 | digitalWrite(pinB, dir > 0);
158 | break;
159 | }
160 | }
161 |
162 | // установить все пины
163 | void setAll(uint8_t val) {
164 | digitalWrite(pinA, val);
165 | digitalWrite(pinB, val);
166 | if (pinC != 255) digitalWrite(pinC, val);
167 | dir = 0;
168 | }
169 |
170 | const uint8_t pinA, pinB, pinC;
171 | bool smooth = 0;
172 | int8_t dir = 0, rev = 1;
173 | uint8_t dead = 0;
174 | int16_t minD = 0, speed = 0, duty = 0, ds = 20;
175 | uint32_t tmr = 0;
176 | };
177 | #endif
--------------------------------------------------------------------------------
/libraries/PS2X_lib/PS2X_lib.cpp:
--------------------------------------------------------------------------------
1 | #include "PS2X_lib.h"
2 | #include
3 | #include
4 | #include
5 | #ifdef __AVR__
6 | #include
7 | #endif
8 | #if ARDUINO > 22
9 | #include "Arduino.h"
10 | #else
11 | #include "WProgram.h"
12 | #include "pins_arduino.h"
13 | #endif
14 |
15 | static byte enter_config[]={0x01,0x43,0x00,0x01,0x00};
16 | static byte set_mode[]={0x01,0x44,0x00,0x01,0x03,0x00,0x00,0x00,0x00};
17 | static byte set_bytes_large[]={0x01,0x4F,0x00,0xFF,0xFF,0x03,0x00,0x00,0x00};
18 | static byte exit_config[]={0x01,0x43,0x00,0x00,0x5A,0x5A,0x5A,0x5A,0x5A};
19 | static byte enable_rumble[]={0x01,0x4D,0x00,0x00,0x01};
20 | static byte type_read[]={0x01,0x45,0x00,0x5A,0x5A,0x5A,0x5A,0x5A,0x5A};
21 |
22 | /****************************************************************************************/
23 | boolean PS2X::NewButtonState() {
24 | return ((last_buttons ^ buttons) > 0);
25 | }
26 |
27 | /****************************************************************************************/
28 | boolean PS2X::NewButtonState(unsigned int button) {
29 | return (((last_buttons ^ buttons) & button) > 0);
30 | }
31 |
32 | /****************************************************************************************/
33 | boolean PS2X::ButtonPressed(unsigned int button) {
34 | return(NewButtonState(button) & Button(button));
35 | }
36 |
37 | /****************************************************************************************/
38 | boolean PS2X::ButtonReleased(unsigned int button) {
39 | return((NewButtonState(button)) & ((~last_buttons & button) > 0));
40 | }
41 |
42 | /****************************************************************************************/
43 | boolean PS2X::Button(uint16_t button) {
44 | return ((~buttons & button) > 0);
45 | }
46 |
47 | /****************************************************************************************/
48 | unsigned int PS2X::ButtonDataByte() {
49 | return (~buttons);
50 | }
51 |
52 | /****************************************************************************************/
53 | byte PS2X::Analog(byte button) {
54 | return PS2data[button];
55 | }
56 |
57 | /****************************************************************************************/
58 | unsigned char PS2X::_gamepad_shiftinout (char byte) {
59 | unsigned char tmp = 0;
60 | for(unsigned char i=0;i<8;i++) {
61 | if(CHK(byte,i)) CMD_SET();
62 | else CMD_CLR();
63 |
64 | CLK_CLR();
65 | delayMicroseconds(CTRL_CLK);
66 |
67 | //if(DAT_CHK()) SET(tmp,i);
68 | if(DAT_CHK()) bitSet(tmp,i);
69 |
70 | CLK_SET();
71 | #if CTRL_CLK_HIGH
72 | delayMicroseconds(CTRL_CLK_HIGH);
73 | #endif
74 | }
75 | CMD_SET();
76 | delayMicroseconds(CTRL_BYTE_DELAY);
77 | return tmp;
78 | }
79 |
80 | /****************************************************************************************/
81 | void PS2X::read_gamepad() {
82 | read_gamepad(false, 0x00);
83 | }
84 |
85 | /****************************************************************************************/
86 | boolean PS2X::read_gamepad(boolean motor1, byte motor2) {
87 | double temp = millis() - last_read;
88 |
89 | if (temp > 1500) //waited to long
90 | reconfig_gamepad();
91 |
92 | if(temp < read_delay) //waited too short
93 | delay(read_delay - temp);
94 |
95 | if(motor2 != 0x00)
96 | motor2 = map(motor2,0,255,0x40,0xFF); //noting below 40 will make it spin
97 |
98 | byte dword[9] = {0x01,0x42,0,motor1,motor2,0,0,0,0};
99 | byte dword2[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
100 |
101 | // Try a few times to get valid data...
102 | for (byte RetryCnt = 0; RetryCnt < 5; RetryCnt++) {
103 | CMD_SET();
104 | CLK_SET();
105 | ATT_CLR(); // low enable joystick
106 |
107 | delayMicroseconds(CTRL_BYTE_DELAY);
108 | //Send the command to send button and joystick data;
109 | for (int i = 0; i<9; i++) {
110 | PS2data[i] = _gamepad_shiftinout(dword[i]);
111 | }
112 |
113 | if(PS2data[1] == 0x79) { //if controller is in full data return mode, get the rest of data
114 | for (int i = 0; i<12; i++) {
115 | PS2data[i+9] = _gamepad_shiftinout(dword2[i]);
116 | }
117 | }
118 |
119 | ATT_SET(); // HI disable joystick
120 | // Check to see if we received valid data or not.
121 | // We should be in analog mode for our data to be valid (analog == 0x7_)
122 | if ((PS2data[1] & 0xf0) == 0x70)
123 | break;
124 |
125 | // If we got to here, we are not in analog mode, try to recover...
126 | reconfig_gamepad(); // try to get back into Analog mode.
127 | delay(read_delay);
128 | }
129 |
130 | // If we get here and still not in analog mode (=0x7_), try increasing the read_delay...
131 | if ((PS2data[1] & 0xf0) != 0x70) {
132 | if (read_delay < 10)
133 | read_delay++; // see if this helps out...
134 | }
135 |
136 | #ifdef PS2X_COM_DEBUG
137 | Serial.print("OUT:IN ");
138 | for(int i=0; i<9; i++){
139 | Serial.print(dword[i], HEX);
140 | Serial.print(":");
141 | Serial.print(PS2data[i], HEX);
142 | Serial.print(" ");
143 | }
144 | for (int i = 0; i<12; i++) {
145 | Serial.print(dword2[i], HEX);
146 | Serial.print(":");
147 | Serial.print(PS2data[i+9], HEX);
148 | Serial.print(" ");
149 | }
150 | Serial.println("");
151 | #endif
152 |
153 | last_buttons = buttons; //store the previous buttons states
154 |
155 | #if defined(__AVR__)
156 | buttons = *(uint16_t*)(PS2data+3); //store as one value for multiple functions
157 | #else
158 | buttons = (uint16_t)(PS2data[4] << 8) + PS2data[3]; //store as one value for multiple functions
159 | #endif
160 | last_read = millis();
161 | return ((PS2data[1] & 0xf0) == 0x70); // 1 = OK = analog mode - 0 = NOK
162 | }
163 |
164 | /****************************************************************************************/
165 | byte PS2X::config_gamepad(uint8_t clk, uint8_t cmd, uint8_t att, uint8_t dat) {
166 | return config_gamepad(clk, cmd, att, dat, false, false);
167 | }
168 |
169 | /****************************************************************************************/
170 | byte PS2X::config_gamepad(uint8_t clk, uint8_t cmd, uint8_t att, uint8_t dat, bool pressures, bool rumble) {
171 |
172 | byte temp[sizeof(type_read)];
173 |
174 | #ifdef __AVR__
175 | _clk_mask = digitalPinToBitMask(clk);
176 | _clk_oreg = portOutputRegister(digitalPinToPort(clk));
177 | _cmd_mask = digitalPinToBitMask(cmd);
178 | _cmd_oreg = portOutputRegister(digitalPinToPort(cmd));
179 | _att_mask = digitalPinToBitMask(att);
180 | _att_oreg = portOutputRegister(digitalPinToPort(att));
181 | _dat_mask = digitalPinToBitMask(dat);
182 | _dat_ireg = portInputRegister(digitalPinToPort(dat));
183 | #else
184 | #ifdef ESP8266
185 | _clk_pin = clk;
186 | _cmd_pin = cmd;
187 | _att_pin = att;
188 | _dat_pin = dat;
189 | #else
190 | uint32_t lport; // Port number for this pin
191 | _clk_mask = digitalPinToBitMask(clk);
192 | lport = digitalPinToPort(clk);
193 | _clk_lport_set = portOutputRegister(lport) + 2;
194 | _clk_lport_clr = portOutputRegister(lport) + 1;
195 |
196 | _cmd_mask = digitalPinToBitMask(cmd);
197 | lport = digitalPinToPort(cmd);
198 | _cmd_lport_set = portOutputRegister(lport) + 2;
199 | _cmd_lport_clr = portOutputRegister(lport) + 1;
200 |
201 | _att_mask = digitalPinToBitMask(att);
202 | lport = digitalPinToPort(att);
203 | _att_lport_set = portOutputRegister(lport) + 2;
204 | _att_lport_clr = portOutputRegister(lport) + 1;
205 |
206 | _dat_mask = digitalPinToBitMask(dat);
207 | _dat_lport = portInputRegister(digitalPinToPort(dat));
208 | #endif
209 | #endif
210 |
211 | pinMode(clk, OUTPUT); //configure ports
212 | pinMode(att, OUTPUT);
213 | pinMode(cmd, OUTPUT);
214 | #ifdef ESP8266
215 | pinMode(dat, INPUT_PULLUP); // enable pull-up
216 | #else
217 | pinMode(dat, INPUT);
218 | #endif
219 |
220 | #if defined(__AVR__)
221 | digitalWrite(dat, HIGH); //enable pull-up
222 | #endif
223 |
224 | CMD_SET(); // SET(*_cmd_oreg,_cmd_mask);
225 | CLK_SET();
226 |
227 | //new error checking. First, read gamepad a few times to see if it's talking
228 | read_gamepad();
229 | read_gamepad();
230 |
231 | //see if it talked - see if mode came back.
232 | //If still anything but 41, 73 or 79, then it's not talking
233 | if(PS2data[1] != 0x41 && PS2data[1] != 0x42 && PS2data[1] != 0x73 && PS2data[1] != 0x79){
234 | #ifdef PS2X_DEBUG
235 | Serial.println("Controller mode not matched or no controller found");
236 | Serial.print("Expected 0x41, 0x42, 0x73 or 0x79, but got ");
237 | Serial.println(PS2data[1], HEX);
238 | #endif
239 | return 1; //return error code 1
240 | }
241 |
242 | //try setting mode, increasing delays if need be.
243 | read_delay = 1;
244 |
245 | for(int y = 0; y <= 10; y++) {
246 | sendCommandString(enter_config, sizeof(enter_config)); //start config run
247 |
248 | //read type
249 | delayMicroseconds(CTRL_BYTE_DELAY);
250 |
251 | CMD_SET();
252 | CLK_SET();
253 | ATT_CLR(); // low enable joystick
254 |
255 | delayMicroseconds(CTRL_BYTE_DELAY);
256 |
257 | for (int i = 0; i<9; i++) {
258 | temp[i] = _gamepad_shiftinout(type_read[i]);
259 | }
260 |
261 | ATT_SET(); // HI disable joystick
262 |
263 | controller_type = temp[3];
264 |
265 | sendCommandString(set_mode, sizeof(set_mode));
266 | if(rumble){ sendCommandString(enable_rumble, sizeof(enable_rumble)); en_Rumble = true; }
267 | if(pressures){ sendCommandString(set_bytes_large, sizeof(set_bytes_large)); en_Pressures = true; }
268 | sendCommandString(exit_config, sizeof(exit_config));
269 |
270 | read_gamepad();
271 |
272 | if(pressures){
273 | if(PS2data[1] == 0x79)
274 | break;
275 | if(PS2data[1] == 0x73)
276 | return 3;
277 | }
278 |
279 | if(PS2data[1] == 0x73)
280 | break;
281 |
282 | if(y == 10){
283 | #ifdef PS2X_DEBUG
284 | Serial.println("Controller not accepting commands");
285 | Serial.print("mode still set at");
286 | Serial.println(PS2data[1], HEX);
287 | #endif
288 | return 2; //exit function with error
289 | }
290 | read_delay += 1; //add 1ms to read_delay
291 | }
292 | return 0; //no error if here
293 | }
294 |
295 | /****************************************************************************************/
296 | void PS2X::sendCommandString(byte string[], byte len) {
297 | #ifdef PS2X_COM_DEBUG
298 | byte temp[len];
299 | ATT_CLR(); // low enable joystick
300 | delayMicroseconds(CTRL_BYTE_DELAY);
301 |
302 | for (int y=0; y < len; y++)
303 | temp[y] = _gamepad_shiftinout(string[y]);
304 |
305 | ATT_SET(); //high disable joystick
306 | delay(read_delay); //wait a few
307 |
308 | Serial.println("OUT:IN Configure");
309 | for(int i=0; i
72 | *
73 | ******************************************************************/
74 |
75 | // $$$$$$$$$$$$ DEBUG ENABLE SECTION $$$$$$$$$$$$$$$$
76 | // to debug ps2 controller, uncomment these two lines to print out debug to uart
77 | //#define PS2X_DEBUG
78 | //#define PS2X_COM_DEBUG
79 |
80 | #ifndef PS2X_lib_h
81 | #define PS2X_lib_h
82 |
83 | #if ARDUINO > 22
84 | #include "Arduino.h"
85 | #else
86 | #include "WProgram.h"
87 | #endif
88 |
89 | #include
90 | #include
91 | #include
92 | #ifdef __AVR__
93 | // AVR
94 | #include
95 | #define CTRL_CLK 8
96 | #define CTRL_BYTE_DELAY 3
97 | #else
98 | #ifdef ESP8266
99 | #define CTRL_CLK 5
100 | #define CTRL_CLK_HIGH 5
101 | #define CTRL_BYTE_DELAY 18
102 | #else
103 | // Pic32...
104 | #include
105 | #define CTRL_CLK 5
106 | #define CTRL_CLK_HIGH 5
107 | #define CTRL_BYTE_DELAY 4
108 | #endif
109 | #endif
110 |
111 | //These are our button constants
112 | #define PSB_SELECT 0x0001
113 | #define PSB_L3 0x0002
114 | #define PSB_R3 0x0004
115 | #define PSB_START 0x0008
116 | #define PSB_PAD_UP 0x0010
117 | #define PSB_PAD_RIGHT 0x0020
118 | #define PSB_PAD_DOWN 0x0040
119 | #define PSB_PAD_LEFT 0x0080
120 | #define PSB_L2 0x0100
121 | #define PSB_R2 0x0200
122 | #define PSB_L1 0x0400
123 | #define PSB_R1 0x0800
124 | #define PSB_GREEN 0x1000
125 | #define PSB_RED 0x2000
126 | #define PSB_BLUE 0x4000
127 | #define PSB_PINK 0x8000
128 | #define PSB_TRIANGLE 0x1000
129 | #define PSB_CIRCLE 0x2000
130 | #define PSB_CROSS 0x4000
131 | #define PSB_SQUARE 0x8000
132 |
133 | //Guitar button constants
134 | #define UP_STRUM 0x0010
135 | #define DOWN_STRUM 0x0040
136 | #define LEFT_STRUM 0x0080
137 | #define RIGHT_STRUM 0x0020
138 | #define STAR_POWER 0x0100
139 | #define GREEN_FRET 0x0200
140 | #define YELLOW_FRET 0x1000
141 | #define RED_FRET 0x2000
142 | #define BLUE_FRET 0x4000
143 | #define ORANGE_FRET 0x8000
144 | #define WHAMMY_BAR 8
145 |
146 | //These are stick values
147 | #define PSS_RX 5
148 | #define PSS_RY 6
149 | #define PSS_LX 7
150 | #define PSS_LY 8
151 |
152 | //These are analog buttons
153 | #define PSAB_PAD_RIGHT 9
154 | #define PSAB_PAD_UP 11
155 | #define PSAB_PAD_DOWN 12
156 | #define PSAB_PAD_LEFT 10
157 | #define PSAB_L2 19
158 | #define PSAB_R2 20
159 | #define PSAB_L1 17
160 | #define PSAB_R1 18
161 | #define PSAB_GREEN 13
162 | #define PSAB_RED 14
163 | #define PSAB_BLUE 15
164 | #define PSAB_PINK 16
165 | #define PSAB_TRIANGLE 13
166 | #define PSAB_CIRCLE 14
167 | #define PSAB_CROSS 15
168 | #define PSAB_SQUARE 16
169 |
170 | #define SET(x,y) (x|=(1<
2 |
3 | PS2X ps2x; // create PS2 Controller Class
4 |
5 | int error = 0;
6 | byte type = 0;
7 | const int ledPin = 11; // Mouse control LED (11 on Teensy 2.0, 13 on Arduino Leonardo)
8 |
9 | // parameters for reading the joystick:
10 | int range = 12; // output range of X or Y movement
11 | int responseDelay = 5; // response delay of the mouse, in ms
12 | int threshold = range/4; // resting threshold
13 | int center = range/2; // resting position value
14 |
15 | boolean mouseIsActive = false; // whether or not to control the mouse
16 | int lastSwitchState = LOW; // previous switch state
17 |
18 | void setup(){
19 | Serial.begin(57600);
20 |
21 | error = ps2x.config_gamepad(15,14,13,12, true, true); //setup pins and settings: GamePad(clock, command, attention, data, Pressures?, Rumble?) check for error
22 |
23 | if(error == 0){
24 | Serial.println("Found Controller, configured successful");
25 | }
26 |
27 | else if(error == 1)
28 | Serial.println("No controller found, check wiring, see readme.txt to enable debug. visit www.billporter.info for troubleshooting tips");
29 |
30 | else if(error == 2)
31 | Serial.println("Controller found but not accepting commands. see readme.txt to enable debug. Visit www.billporter.info for troubleshooting tips");
32 |
33 | else if(error == 3)
34 | Serial.println("Controller refusing to enter Pressures mode, may not support it. ");
35 |
36 | type = ps2x.readType();
37 | switch(type) {
38 | case 0:
39 | Serial.println("Unknown Controller type");
40 | break;
41 | case 1:
42 | Serial.println("DualShock Controller Found");
43 | break;
44 | case 2:
45 | Serial.println("GuitarHero Controller Found");
46 | break;
47 | }
48 |
49 | // take control of the mouse:
50 | Mouse.begin();
51 | Keyboard.begin();
52 | }
53 |
54 | void loop()
55 | {
56 |
57 | if(error == 1) //skip loop if no controller found
58 | return;
59 |
60 | ps2x.read_gamepad(false, 0); //read controller and set large motor to spin at 'vibrate' speed
61 |
62 | // read the switch:
63 | int switchState = ps2x.ButtonPressed(PSB_RED);
64 | // if it's changed and it's high, toggle the mouse state:
65 | if (switchState != lastSwitchState) {
66 | if (switchState == HIGH) {
67 | mouseIsActive = !mouseIsActive;
68 | // turn on LED to indicate mouse state:
69 | digitalWrite(ledPin, mouseIsActive);
70 | }
71 | }
72 | // save switch state for next comparison:
73 | lastSwitchState = switchState;
74 |
75 | // read and scale the two axes:
76 | int xReading = readAxis(PSS_LX);
77 | int yReading = readAxis(PSS_LY);
78 |
79 | // if the mouse control state is active, move the mouse:
80 | if (mouseIsActive) {
81 | Mouse.move(xReading, yReading, 0);
82 | }
83 |
84 | // read the mouse button and click or not click:
85 | // if the mouse button is pressed:
86 | if (ps2x.ButtonPressed(PSB_BLUE)) {
87 | // if the mouse is not pressed, press it:
88 | if (!Mouse.isPressed(MOUSE_LEFT)) {
89 | Mouse.press(MOUSE_LEFT);
90 | }
91 | }
92 | // else the mouse button is not pressed:
93 | else {
94 | // if the mouse is pressed, release it:
95 | if (Mouse.isPressed(MOUSE_LEFT)) {
96 | Mouse.release(MOUSE_LEFT);
97 | }
98 | }
99 |
100 | if (ps2x.Button(PSB_PAD_UP)) {
101 | Keyboard.press(KEY_UP_ARROW);
102 | } else {
103 | Keyboard.release(KEY_UP_ARROW);
104 | }
105 |
106 | if (ps2x.Button(PSB_PAD_DOWN)) {
107 | Keyboard.press(KEY_DOWN_ARROW);
108 | } else {
109 | Keyboard.release(KEY_DOWN_ARROW);
110 | }
111 |
112 | if (ps2x.Button(PSB_PAD_RIGHT)) {
113 | Keyboard.press(KEY_RIGHT_ARROW);
114 | } else {
115 | Keyboard.release(KEY_RIGHT_ARROW);
116 | }
117 |
118 | if (ps2x.Button(PSB_PAD_LEFT)) {
119 | Keyboard.press(KEY_LEFT_ARROW);
120 | } else {
121 | Keyboard.release(KEY_LEFT_ARROW);
122 | }
123 |
124 | delay(5);
125 |
126 | }
127 |
128 | /*
129 | reads an axis (0 or 1 for x or y) and scales the
130 | analog input range to a range from 0 to
131 | */
132 |
133 | int readAxis(int thisAxis) {
134 | // read the analog input:
135 | int reading = ps2x.Analog(thisAxis);
136 |
137 | // map the reading from the analog input range to the output range:
138 | reading = map(reading, 0, 255, 0, range);
139 |
140 | // if the output reading is outside from the
141 | // rest position threshold, use it:
142 | int distance = reading - center;
143 |
144 | if (abs(distance) < threshold) {
145 | distance = 0;
146 | }
147 |
148 | // return the distance for this axis:
149 | return distance;
150 | }
151 |
--------------------------------------------------------------------------------
/libraries/PS2X_lib/examples/PS2X_Example/PS2X_Example.ino:
--------------------------------------------------------------------------------
1 | #include //for v1.6
2 |
3 | /******************************************************************
4 | * set pins connected to PS2 controller:
5 | * - 1e column: original
6 | * - 2e colmun: Stef?
7 | * replace pin numbers by the ones you use
8 | ******************************************************************/
9 | #define PS2_DAT 13 //14
10 | #define PS2_CMD 11 //15
11 | #define PS2_SEL 10 //16
12 | #define PS2_CLK 12 //17
13 |
14 | /******************************************************************
15 | * select modes of PS2 controller:
16 | * - pressures = analog reading of push-butttons
17 | * - rumble = motor rumbling
18 | * uncomment 1 of the lines for each mode selection
19 | ******************************************************************/
20 | //#define pressures true
21 | #define pressures false
22 | //#define rumble true
23 | #define rumble false
24 |
25 | PS2X ps2x; // create PS2 Controller Class
26 |
27 | //right now, the library does NOT support hot pluggable controllers, meaning
28 | //you must always either restart your Arduino after you connect the controller,
29 | //or call config_gamepad(pins) again after connecting the controller.
30 |
31 | int error = 0;
32 | byte type = 0;
33 | byte vibrate = 0;
34 |
35 | void setup(){
36 |
37 | Serial.begin(57600);
38 |
39 | delay(300); //added delay to give wireless ps2 module some time to startup, before configuring it
40 |
41 | //CHANGES for v1.6 HERE!!! **************PAY ATTENTION*************
42 |
43 | //setup pins and settings: GamePad(clock, command, attention, data, Pressures?, Rumble?) check for error
44 | error = ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT, pressures, rumble);
45 |
46 | if(error == 0){
47 | Serial.print("Found Controller, configured successful ");
48 | Serial.print("pressures = ");
49 | if (pressures)
50 | Serial.println("true ");
51 | else
52 | Serial.println("false");
53 | Serial.print("rumble = ");
54 | if (rumble)
55 | Serial.println("true)");
56 | else
57 | Serial.println("false");
58 | Serial.println("Try out all the buttons, X will vibrate the controller, faster as you press harder;");
59 | Serial.println("holding L1 or R1 will print out the analog stick values.");
60 | Serial.println("Note: Go to www.billporter.info for updates and to report bugs.");
61 | }
62 | else if(error == 1)
63 | Serial.println("No controller found, check wiring, see readme.txt to enable debug. visit www.billporter.info for troubleshooting tips");
64 |
65 | else if(error == 2)
66 | Serial.println("Controller found but not accepting commands. see readme.txt to enable debug. Visit www.billporter.info for troubleshooting tips");
67 |
68 | else if(error == 3)
69 | Serial.println("Controller refusing to enter Pressures mode, may not support it. ");
70 |
71 | // Serial.print(ps2x.Analog(1), HEX);
72 |
73 | type = ps2x.readType();
74 | switch(type) {
75 | case 0:
76 | Serial.print("Unknown Controller type found ");
77 | break;
78 | case 1:
79 | Serial.print("DualShock Controller found ");
80 | break;
81 | case 2:
82 | Serial.print("GuitarHero Controller found ");
83 | break;
84 | case 3:
85 | Serial.print("Wireless Sony DualShock Controller found ");
86 | break;
87 | }
88 | }
89 |
90 | void loop() {
91 | /* You must Read Gamepad to get new values and set vibration values
92 | ps2x.read_gamepad(small motor on/off, larger motor strenght from 0-255)
93 | if you don't enable the rumble, use ps2x.read_gamepad(); with no values
94 | You should call this at least once a second
95 | */
96 | if(error == 1) //skip loop if no controller found
97 | return;
98 |
99 | if(type == 2){ //Guitar Hero Controller
100 | ps2x.read_gamepad(); //read controller
101 |
102 | if(ps2x.ButtonPressed(GREEN_FRET))
103 | Serial.println("Green Fret Pressed");
104 | if(ps2x.ButtonPressed(RED_FRET))
105 | Serial.println("Red Fret Pressed");
106 | if(ps2x.ButtonPressed(YELLOW_FRET))
107 | Serial.println("Yellow Fret Pressed");
108 | if(ps2x.ButtonPressed(BLUE_FRET))
109 | Serial.println("Blue Fret Pressed");
110 | if(ps2x.ButtonPressed(ORANGE_FRET))
111 | Serial.println("Orange Fret Pressed");
112 |
113 | if(ps2x.ButtonPressed(STAR_POWER))
114 | Serial.println("Star Power Command");
115 |
116 | if(ps2x.Button(UP_STRUM)) //will be TRUE as long as button is pressed
117 | Serial.println("Up Strum");
118 | if(ps2x.Button(DOWN_STRUM))
119 | Serial.println("DOWN Strum");
120 |
121 | if(ps2x.Button(PSB_START)) //will be TRUE as long as button is pressed
122 | Serial.println("Start is being held");
123 | if(ps2x.Button(PSB_SELECT))
124 | Serial.println("Select is being held");
125 |
126 | if(ps2x.Button(ORANGE_FRET)) { // print stick value IF TRUE
127 | Serial.print("Wammy Bar Position:");
128 | Serial.println(ps2x.Analog(WHAMMY_BAR), DEC);
129 | }
130 | }
131 | else { //DualShock Controller
132 | ps2x.read_gamepad(false, vibrate); //read controller and set large motor to spin at 'vibrate' speed
133 |
134 | if(ps2x.Button(PSB_START)) //will be TRUE as long as button is pressed
135 | Serial.println("Start is being held");
136 | if(ps2x.Button(PSB_SELECT))
137 | Serial.println("Select is being held");
138 |
139 | if(ps2x.Button(PSB_PAD_UP)) { //will be TRUE as long as button is pressed
140 | Serial.print("Up held this hard: ");
141 | Serial.println(ps2x.Analog(PSAB_PAD_UP), DEC);
142 | }
143 | if(ps2x.Button(PSB_PAD_RIGHT)){
144 | Serial.print("Right held this hard: ");
145 | Serial.println(ps2x.Analog(PSAB_PAD_RIGHT), DEC);
146 | }
147 | if(ps2x.Button(PSB_PAD_LEFT)){
148 | Serial.print("LEFT held this hard: ");
149 | Serial.println(ps2x.Analog(PSAB_PAD_LEFT), DEC);
150 | }
151 | if(ps2x.Button(PSB_PAD_DOWN)){
152 | Serial.print("DOWN held this hard: ");
153 | Serial.println(ps2x.Analog(PSAB_PAD_DOWN), DEC);
154 | }
155 |
156 | vibrate = ps2x.Analog(PSAB_CROSS); //this will set the large motor vibrate speed based on how hard you press the blue (X) button
157 | if (ps2x.NewButtonState()) { //will be TRUE if any button changes state (on to off, or off to on)
158 | if(ps2x.Button(PSB_L3))
159 | Serial.println("L3 pressed");
160 | if(ps2x.Button(PSB_R3))
161 | Serial.println("R3 pressed");
162 | if(ps2x.Button(PSB_L2))
163 | Serial.println("L2 pressed");
164 | if(ps2x.Button(PSB_R2))
165 | Serial.println("R2 pressed");
166 | if(ps2x.Button(PSB_TRIANGLE))
167 | Serial.println("Triangle pressed");
168 | }
169 |
170 | if(ps2x.ButtonPressed(PSB_CIRCLE)) //will be TRUE if button was JUST pressed
171 | Serial.println("Circle just pressed");
172 | if(ps2x.NewButtonState(PSB_CROSS)) //will be TRUE if button was JUST pressed OR released
173 | Serial.println("X just changed");
174 | if(ps2x.ButtonReleased(PSB_SQUARE)) //will be TRUE if button was JUST released
175 | Serial.println("Square just released");
176 |
177 | if(ps2x.Button(PSB_L1) || ps2x.Button(PSB_R1)) { //print stick values if either is TRUE
178 | Serial.print("Stick Values:");
179 | Serial.print(ps2x.Analog(PSS_LY), DEC); //Left stick, Y axis. Other options: LX, RY, RX
180 | Serial.print(",");
181 | Serial.print(ps2x.Analog(PSS_LX), DEC);
182 | Serial.print(",");
183 | Serial.print(ps2x.Analog(PSS_RY), DEC);
184 | Serial.print(",");
185 | Serial.println(ps2x.Analog(PSS_RX), DEC);
186 | }
187 | }
188 | delay(50);
189 | }
190 |
--------------------------------------------------------------------------------
/libraries/PS2X_lib/keywords.txt:
--------------------------------------------------------------------------------
1 | #######################################
2 | # Syntax Coloring Map PS2X
3 | #######################################
4 |
5 | #######################################
6 | # Datatypes (KEYWORD1)
7 | #######################################
8 |
9 | PS2X KEYWORD1
10 |
11 | #######################################
12 | # Methods and Functions (KEYWORD2)
13 | #######################################
14 | Button KEYWORD2
15 | ButtonDataByte KEYWORD2
16 | NewButtonState KEYWORD2
17 | ButtonPressed KEYWORD2
18 | ButtonReleased KEYWORD2
19 | read_gamepad KEYWORD2
20 | config_gamepad KEYWORD2
21 | enableRumble KEYWORD2
22 | enablePressures KEYWORD2
23 | Analog KEYWORD2
24 |
25 | #######################################
26 | # Constants (LITERAL1)
27 | #######################################
28 | PSB_SELECT LITERAL1
29 | PSB_L3 LITERAL1
30 | PSB_R3 LITERAL1
31 | PSB_START LITERAL1
32 | PSB_PAD_UP LITERAL1
33 | PSB_PAD_RIGHT LITERAL1
34 | PSB_PAD_DOWN LITERAL1
35 | PSB_PAD_LEFT LITERAL1
36 | PSB_L2 LITERAL1
37 | PSB_R2 LITERAL1
38 | PSB_L1 LITERAL1
39 | PSB_R1 LITERAL1
40 | PSB_GREEN LITERAL1
41 | PSB_RED LITERAL1
42 | PSB_BLUE LITERAL1
43 | PSB_PINK LITERAL1
44 | PSB_TRIANGLE LITERAL1
45 | PSB_CIRCLE LITERAL1
46 | PSB_CROSS LITERAL1
47 | PSB_SQUARE LITERAL1
48 | PSS_RX LITERAL1
49 | PSS_RY LITERAL1
50 | PSS_LX LITERAL1
51 | PSS_LY LITERAL1
52 |
53 | PSAB_PAD_RIGHT LITERAL1
54 | PSAB_PAD_UP LITERAL1
55 | PSAB_PAD_DOWN LITERAL1
56 | PSAB_PAD_LEFT LITERAL1
57 | PSAB_L2 LITERAL1
58 | PSAB_R2 LITERAL1
59 | PSAB_L1 LITERAL1
60 | PSAB_R1 LITERAL1
61 | PSAB_GREEN LITERAL1
62 | PSAB_RED LITERAL1
63 | PSAB_BLUE LITERAL1
64 | PSAB_PINK LITERAL1
65 | PSAB_TRIANGLE LITERAL1
66 | PSAB_CIRCLE LITERAL1
67 | PSAB_CROSS LITERAL1
68 | PSAB_SQUARE LITERAL1
69 |
70 | GREEN_FRET LITERAL1
71 | RED_FRET LITERAL1
72 | YELLOW_FRET LITERAL1
73 | BLUE_FRET LITERAL1
74 | ORANGE_FRET LITERAL1
75 | STAR_POWER LITERAL1
76 | UP_STRUM LITERAL1
77 | DOWN_STRUM LITERAL1
78 | WHAMMY_BAR LITERAL1
79 |
--------------------------------------------------------------------------------
/schemes/scheme.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/AlexGyver/MecanumBot/dfd2164ae9db8b4dd4962f0753cf5bd1c7a2e279/schemes/scheme.jpg
--------------------------------------------------------------------------------
/schemes/scheme2.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/AlexGyver/MecanumBot/dfd2164ae9db8b4dd4962f0753cf5bd1c7a2e279/schemes/scheme2.jpg
--------------------------------------------------------------------------------