Datasheet
Chapter 6 • Light-Sensitive Navigation with Phototransistors
208 • Robotics with the BOE Shield-Bot
speedLeft = int(200.0 - (ndShade * 1000.0));
speedLeft = constrain(speedLeft, -200, 200);
speedRight = 200; // Full speed right wheel
}
else // Shade on Left?
{ // Slow down right wheel
speedRight = int(200.0 + (ndShade * 1000.0));
speedRight = constrain(speedRight, -200, 200);
speedLeft = 200; // Full speed left wheel
}
maneuver(speedLeft, speedRight, 20); // Set wheel speeds
}
long rcTime(int pin) // rcTime measures decay at pin
{
pinMode(pin, OUTPUT); // Charge capacitor
digitalWrite(pin, HIGH); // ..by setting pin ouput-high
delay(5); // ..for 5 ms
pinMode(pin, INPUT); // Set pin to input
digitalWrite(pin, LOW); // ..with no pullup
long time = micros(); // Mark the time
while(digitalRead(pin)); // Wait for voltage < threshold
time = micros() - time; // Calculate decay time
return time; // Returns decay time
}
// maneuver function
void maneuver(int speedLeft, int speedRight, int msTime)
{
servoLeft.writeMicroseconds(1500 + speedLeft); // Left servo speed
servoRight.writeMicroseconds(1500 - speedRight); // Right servo speed
if(msTime==-1) // If msTime = -1
{
servoLeft.detach(); // Stop servo signals
servoRight.detach();
}
delay(msTime); // Delay for msTime
}
Your Turn – Light/Shade Sensitivity Adjustments
If you want more sensitivity to light, change 1000 to a larger value in these two
commands:
speedLeft = int(200.0 - (ndShade * 1000.0));
speedRight = int(200.0 + (ndShade * 1000.0));
Want less light sensitivity? Change 1000 to a smaller value.
Try it.