#include <Servo.h> //Geworkian Michael, July 2024. Only Int type (vs. robotclass). "Tested for Uno, Nano"
Servo servo_y2; Servo servo_x;
Servo servo_y; Servo servo_clamp;//Клешня
// начальные углы сервомоторов
int x_grad = 0;/*Высота */ int y_grad = 90; // Длина
int clamp_grad = 90;/*Клешня */ int y2_grad = 90;//Вращение базы.
void setup() { Serial.begin(9600); // 11,10,9,5: реальные пины серво на шилде
servo_y2.attach(11); servo_y2.write(y2_grad); // Ось_1 Вращение базы
servo_clamp.attach(5); servo_clamp.write(clamp_grad); // Клешня
servo_x.attach(10); servo_x.write(x_grad); // Ось_2 Высота (Плечо1)
servo_y.attach(9); servo_y.write(y_grad); } // Ось_3 Длина (Плечо2)
void loop() {
int left_joystick_x2 = analogRead(A0); // левый горизон-й (Клешня)(у Тёмы наоборот, опечатка)
int left_joystick_y = analogRead(A1); // левый вертик-й (Длина)(у Тёмы наоборот, опечатка)
int right_joystick_x = analogRead(A2); // правый вертикальный (Высота)
int right_joystick_y2 = analogRead(A3); // правый горизонтальный (Вращение базы)
if (left_joystick_y < 400) y_grad -= 7;
else if (left_joystick_y > 600) y_grad += 7;
if (left_joystick_x2 < 400) clamp_grad -= 5;
else if (left_joystick_x2 > 600) clamp_grad += 5;
if (right_joystick_x < 400) x_grad -= 7;
else if (right_joystick_x > 600) x_grad += 7;
if (right_joystick_y2 < 400) y2_grad -= 7;
else if (right_joystick_y2 > 600) y2_grad += 7;
if(y_grad<45) y_grad=45; if(y_grad>135) y_grad=135; // Длина. Старый вариант 5...150
if(x_grad<0) x_grad=0; if(x_grad>45) x_grad=45; // Высота. Старый вариант 40...175 (Из robotclass)
if(y2_grad<0) y2_grad=0; if(y2_grad>180) y2_grad=180; // Вращение базы. Старый вариант 15...145
if(clamp_grad<75) clamp_grad=75; if(y_grad>90) y_grad=90; // Клешня. ИСПРАВИЛ, был вариант 70...135,
Serial.print(" x_grad:"); Serial.print(x_grad);
Serial.print(", y_grad:"); Serial.print(y_grad);
Serial.print(", y2_grad:"); Serial.print(y2_grad);
Serial.print(", clamp_grad:"); Serial.println(clamp_grad);
servo_clamp.write(clamp_grad); servo_x.write(x_grad);
servo_y.write(y_grad); servo_y2.write(y2_grad);
delay(15); // Увеличить? Время надо подбирать
}
X2
L-joystick
R-joystick
X
Y2
Y
Вверх
Вниз
Вниз
Вверх
Вверх
Вниз
Вниз
Вверх
Вращение базы
Высота
Длина
Клешня