/
/
2PiR
wheel distance = 157.48mm
2Pi(157.48)=989.47
1/4 turn = 989.47/4 = 247.37
247counts for 1/4 turn or 120 per encoder to turn in place
****************************/
#include <RedBot.h>
RedBotMotors motors;
RedBotEncoder encoder = RedBotEncoder(A2, 10);
int buttonPin = 12;
int countsPerRev = 192; // 4 pairs of N-S x 48:1 gearbox = 192 ticks per wheel rev
float wheelDiam = 2.56; // diam = 65mm / 25.4 mm/in
float wheelCirc = PI * wheelDiam; // Redbot wheel circumference = pi*D
void setup()
{
pinMode(buttonPin, INPUT_PULLUP);
Serial.begin(9600);
}
void loop(void)
{
// set the power for left & right motors on button press
if (digitalRead(buttonPin) == LOW)
{
turn();
}
}
void turn()
{
long lCount = 0;
long rCount = 0;
long targetCount;
float numRev;
motors.leftMotor(-80);
motors.rightMotor(0);
// variables for tracking the left and right encoder counts
long prevlCount, prevrCount;
long lDiff, rDiff; // diff between current encoder count and previous count
encoder.clearEnc(BOTH); // clear the encoder count
delay(100); // short delay before starting the motors.
while (rCount < 240)
{
// while the right encoder is less than the target count – debug print
// the encoder values and wait – this is a holding loop.
lCount = encoder.getTicks(LEFT);
rCount = encoder.getTicks(RIGHT);
Serial.print(lCount);
Serial.print("\t");
Serial.print(rCount);
Serial.print("\t");
Serial.println(targetCount);
// calculate the rotation “speed” as a difference in the count from previous cycle.
lDiff = (lCount - prevlCount);
rDiff = (rCount - prevrCount);
// store the current count as the “previous” count for the next cycle.
prevlCount = lCount;
prevrCount = rCount;
}
delay(50); // short delay to give motors a chance to respond.
}