Add DisplayLib for OLED display management and enhance motor control with rotation methods
This commit is contained in:
parent
4841dc4317
commit
5d0a067fba
6 changed files with 207 additions and 21 deletions
|
@ -8,7 +8,7 @@ OmniWheelMotors::OmniWheelMotors(int m1_r_pwm, int m1_l_pwm,
|
|||
motor_3 = {m3_r_pwm, m3_l_pwm};
|
||||
|
||||
MAX_SPEED = 70; // Max PWM value
|
||||
MIN_SPEED = 50; // Default minimum speed
|
||||
MIN_SPEED = 255; // Default minimum speed
|
||||
FULL_ROTATION_TIME = 2000; // Default time for 360 degrees in milliseconds
|
||||
}
|
||||
|
||||
|
@ -85,8 +85,8 @@ void OmniWheelMotors::moveRight(int speed) {
|
|||
void OmniWheelMotors::rotate360() {
|
||||
// Set motor directions for full rotation
|
||||
setMotorSpeed(motor_1, 0, MIN_SPEED); // Motor 1 forward
|
||||
setMotorSpeed(motor_2, 0, MIN_SPEED); // Motor 2 forward
|
||||
setMotorSpeed(motor_3, 0, 0); // Motor 3 neutral
|
||||
setMotorSpeed(motor_2, MIN_SPEED, 0); // Motor 2 forward
|
||||
setMotorSpeed(motor_3, 0, MIN_SPEED); // Motor 3 neutral
|
||||
|
||||
// Wait for approximately one full rotation
|
||||
delay(FULL_ROTATION_TIME);
|
||||
|
@ -95,6 +95,26 @@ void OmniWheelMotors::rotate360() {
|
|||
stop();
|
||||
}
|
||||
|
||||
void OmniWheelMotors::rotateClockwise(int speed) {
|
||||
// Ensure speed is at least minimum speed for stable movement
|
||||
speed = max(speed, MIN_SPEED);
|
||||
|
||||
// Set motor directions for clockwise rotation
|
||||
setMotorSpeed(motor_1, 0, speed); // Motor 1 forward
|
||||
setMotorSpeed(motor_2, speed, 0); // Motor 2 backward
|
||||
setMotorSpeed(motor_3, speed, 0); // Motor 3 neutral
|
||||
}
|
||||
|
||||
void OmniWheelMotors::rotateCounterClockwise(int speed) {
|
||||
// Ensure speed is at least minimum speed for stable movement
|
||||
speed = max(speed, MIN_SPEED);
|
||||
|
||||
// Set motor directions for counter-clockwise rotation
|
||||
setMotorSpeed(motor_1, speed, 0); // Motor 1 backward
|
||||
setMotorSpeed(motor_2, 0, speed); // Motor 2 forward
|
||||
setMotorSpeed(motor_3, 0, speed); // Motor 3 neutral
|
||||
}
|
||||
|
||||
void OmniWheelMotors::rotateToAngle(int targetAngle) {
|
||||
// Ensure angle is between 0 and 360
|
||||
targetAngle = targetAngle % 360;
|
||||
|
|
|
@ -23,7 +23,8 @@ public:
|
|||
void moveBackward(int speed);
|
||||
void moveLeft(int speed);
|
||||
void moveRight(int speed);
|
||||
|
||||
void rotateClockwise(int speed);
|
||||
void rotateCounterClockwise(int speed);
|
||||
// Rotation functions
|
||||
void rotate360();
|
||||
void rotateToAngle(int targetAngle);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue