Skip to content
This repository was archived by the owner on Jul 25, 2022. It is now read-only.

Commit 7226255

Browse files
committed
Fixed backward / forward direction.
This is because the robot is now operated backwards by default.
1 parent 0ce2217 commit 7226255

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

robot-control-src/Drives.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -61,8 +61,8 @@ static Amplitude calcRightSpeed(const Amplitude leftSpeed)
6161
void rotateCounter(const Counter steps, const Amplitude amplitude, bool const clockwise)
6262
{
6363
lastAction = clockwise ? Action::TURN_RIGHT : Action::TURN_LEFT;
64-
LeftDrive::drive(steps, amplitude, !clockwise);
65-
RightDrive::drive(steps, calcRightSpeed(amplitude), clockwise);
64+
LeftDrive::drive(steps, amplitude, clockwise);
65+
RightDrive::drive(steps, calcRightSpeed(amplitude), !clockwise);
6666
}
6767

6868
void driveCounter(const Counter steps, const Amplitude amplitude, const bool backwards)

robot-control-src/Drives.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class Drive
6363
counter = 0;
6464
target = distance;
6565
isIdle = false;
66-
digitalWrite(directionPin, backwards ? LOW : HIGH);
66+
digitalWrite(directionPin, !backwards ? LOW : HIGH);
6767
analogWrite(motorControlpin, std::min(maxAmplitude, amplitude));
6868
}
6969
};

0 commit comments

Comments
 (0)