first commit

This commit is contained in:
Ghassan Yusuf 2025-03-23 00:22:24 +03:00
commit d86f52432c
3 changed files with 365 additions and 0 deletions

102
ESP32_MOTOR_SERVO.ino Normal file
View File

@ -0,0 +1,102 @@
#include "L298N_ESP32.h"
#include "Servo_ESP32.h"
// Motor pins
#define MOTOR1_PIN1 27
#define MOTOR1_PIN2 26
#define MOTOR1_ENABLE 14
#define MOTOR2_PIN1 25
#define MOTOR2_PIN2 33
#define MOTOR2_ENABLE 32
// Servo pins
#define SERVO1_PIN 13
#define SERVO2_PIN 12
// Create motor objects
L298N_ESP32 motor1(MOTOR1_PIN1, MOTOR1_PIN2, MOTOR1_ENABLE, 0);
L298N_ESP32 motor2(MOTOR2_PIN1, MOTOR2_PIN2, MOTOR2_ENABLE, 1);
// Create servo objects (using PWM channels 2 and 3)
Servo_ESP32 servo1(SERVO1_PIN, 2);
Servo_ESP32 servo2(SERVO2_PIN, 3);
void setup() {
Serial.begin(115200);
// Initialize motors
motor1.begin();
motor2.begin();
motor1.setMin(50); // Set minimum speed for motor1
motor1.setMax(200); // Set maximum speed for motor1
motor2.setMin(50); // Set minimum speed for motor2
motor2.setMax(200); // Set maximum speed for motor2
// Initialize servos
servo1.begin();
servo2.begin();
servo1.setMin(10); // Set minimum position for servo1
servo1.setMax(170); // Set maximum position for servo1
servo2.setMin(20); // Set minimum position for servo2
servo2.setMax(160); // Set maximum position for servo2
Serial.println("Motors and servos initialized");
}
void loop() {
// Move motors forward and sweep servos
Serial.println("Moving motors forward and sweeping servos...");
motor1.forward();
motor2.forward();
motor1.setPercentage(75); // Set motor1 speed to 75%
motor2.setPercentage(75); // Set motor2 speed to 75%
servo1.sweep(10, 170, 15); // Sweep servo1 from position 10 to position 170 with a delay of 15ms between steps
servo2.sweep(20, 160, 15); // Sweep servo2 from position 20 to position 160 with a delay of 15ms between steps
delay(2000);
// Stop motors and center servos
Serial.println("Stopping motors and centering servos...");
motor1.stop();
motor2.stop();
servo1.goInit(); // Move servo1 to its initial (center) position
servo2.goInit(); // Move servo2 to its initial (center) position
delay(1000);
// Move motors backward and control servos using percentages
Serial.println("Moving motors backward and controlling servos by percentage...");
motor1.backward();
motor2.backward();
motor1.goMin(); // Run motor1 at its minimum speed
motor2.goMin(); // Run motor2 at its minimum speed
for (int i = 0; i <= 100; i += 10) {
servo1.percent(i); // Move servo1 to a percentage of its range (0% to max)
servo2.percent(100 - i); // Move servo2 to the opposite percentage of its range (max to min)
delay(200);
}
delay(2000);
// Stop all motors and reset servos to center positions
Serial.println("Stopping all motors and resetting servos...");
motor1.stop();
motor2.stop();
servo1.goInit(); // Reset servo1 to center position
servo2.goInit(); // Reset servo2 to center position
delay(1000);
}

128
L298N_ESP32.h Normal file
View File

@ -0,0 +1,128 @@
#ifndef L298N_ESP32_h
#define L298N_ESP32_h
#include <Arduino.h>
class L298N_ESP32 {
private:
uint8_t in1Pin;
uint8_t in2Pin;
uint8_t enPin;
uint8_t pwmChannel;
uint8_t _speed;
uint8_t _min_speed = 0;
uint8_t _max_speed = 255;
bool _invert = false;
void checkWrite(uint8_t value) {
if (_speed != value) {
_speed = value;
ledcWrite(enPin, _speed);
}
}
public:
L298N_ESP32(uint8_t in1, uint8_t in2, uint8_t en, uint8_t channel = 0) :
in1Pin(in1), in2Pin(in2), enPin(en), pwmChannel(channel), _speed(0) {}
void begin() {
pinMode(in1Pin, OUTPUT);
pinMode(in2Pin, OUTPUT);
ledcAttachChannel(enPin, 30000, 8, pwmChannel); // 30kHz frequency, 8-bit resolution
digitalWrite(in1Pin, LOW);
digitalWrite(in2Pin, LOW);
checkWrite(0);
}
void setMin(uint8_t value) {
_min_speed = value;
}
void setMax(uint8_t value) {
_max_speed = value;
}
void invert() {
_invert = !_invert;
}
void forward() {
if (!_invert) {
digitalWrite(in1Pin, LOW);
digitalWrite(in2Pin, HIGH);
} else {
digitalWrite(in1Pin, HIGH);
digitalWrite(in2Pin, LOW);
}
}
void backward() {
if (!_invert) {
digitalWrite(in1Pin, HIGH);
digitalWrite(in2Pin, LOW);
} else {
digitalWrite(in1Pin, LOW);
digitalWrite(in2Pin, HIGH);
}
}
void goMin() {
checkWrite(_min_speed);
}
void goMax() {
checkWrite(_max_speed);
}
void setSpeed(uint8_t speed) {
speed = constrain(speed, _min_speed, _max_speed);
checkWrite(speed);
}
void setPercentage(uint8_t percentage) {
if (percentage == 0) {
checkWrite(0);
} else {
uint8_t speed = map(percentage, 1, 100, _min_speed, _max_speed);
checkWrite(speed);
}
}
void override(uint8_t value) {
ledcWrite(enPin, value);
}
void stop() {
digitalWrite(in1Pin, LOW);
digitalWrite(in2Pin, LOW);
checkWrite(0);
}
unsigned int command(Stream &serial) {
unsigned int lastTriedValue = 0;
while (true) {
serial.print("Enter PWM value (0-255) or 'exit': ");
while (!serial.available()) {}
if (serial.available()) {
String input = serial.readStringUntil('\n');
serial.readString(); // Clear buffer
input.trim();
if (input.equalsIgnoreCase("exit")) {
serial.println("Exiting command function");
stop();
return lastTriedValue;
}
int value = input.toInt();
if (value >= 0 && value <= 255) {
lastTriedValue = value;
serial.println(lastTriedValue);
setSpeed(lastTriedValue);
} else {
serial.println("Invalid input. Please enter a value between 0 and 255.");
}
}
}
}
};
#endif

135
Servo_ESP32.h Normal file
View File

@ -0,0 +1,135 @@
#ifndef Servo_ESP32_h
#define Servo_ESP32_h
#include <Arduino.h>
class Servo_ESP32 {
private:
uint8_t servoPin;
uint8_t pwmChannel;
int minPulseWidth;
int maxPulseWidth;
int currentAngle;
const int freq = 50; // 50Hz for standard servos
const int resolution = 16; // 16-bit resolution for smoother control
bool _invert = false;
uint8_t _min_pos = 0;
uint8_t _max_pos = 180;
uint8_t _init_pos = 90;
uint8_t _prv_pos = 0;
bool verify(uint8_t input) {
if (input != _prv_pos) {
_prv_pos = input;
return true;
}
return false;
}
public:
Servo_ESP32() {}
Servo_ESP32(uint8_t pin, uint8_t channel, int minPulse = 500, int maxPulse = 2500) :
servoPin(pin), pwmChannel(channel), minPulseWidth(minPulse), maxPulseWidth(maxPulse), currentAngle(0) {}
void begin() {
ledcAttachChannel(servoPin, freq, resolution, pwmChannel);
write(_init_pos);
}
void setPin(uint8_t pin) {
servoPin = pin;
}
void invert() {
_invert = !_invert;
}
void setMin(uint8_t start) {
_min_pos = start;
}
void setMax(uint8_t stop) {
_max_pos = stop;
}
void setInit(uint8_t init) {
_init_pos = init;
}
void goMax() {
write(_max_pos);
}
void goMin() {
write(_min_pos);
}
void goInit() {
write(_init_pos);
}
void write(int angle) {
if (!verify(angle)) return;
currentAngle = _invert ? 180 - angle : angle;
currentAngle = constrain(currentAngle, 0, 180);
int dutyCycle = map(currentAngle, 0, 180,
minPulseWidth * (65536 / 20000),
maxPulseWidth * (65536 / 20000));
ledcWrite(pwmChannel, dutyCycle);
}
int read() {
return currentAngle;
}
void command(Stream &serial) {
serial.print("Enter position value: ");
while (!serial.available()) {}
if (serial.available()) {
String x = serial.readStringUntil('\n');
while (serial.available()) {
serial.read();
}
serial.println();
x.trim();
serial.println(x);
write(x.toInt());
}
}
void move(uint8_t pos) {
pos = constrain(pos, _min_pos, _max_pos);
write(pos);
}
void percent(uint8_t pos) {
pos = map(pos, 0, 100, _min_pos, _max_pos);
write(pos);
}
void sweep(uint8_t start, uint8_t stop, unsigned int mDelay) {
if (start < stop) {
for (int i = start; i <= stop; i++) {
move(i);
delay(mDelay);
}
} else if (start > stop) {
for (int i = start; i >= stop; i--) {
move(i);
delay(mDelay);
}
}
}
void override(uint8_t pos) {
write(pos);
}
};
#endif