Activity 4: Test a Light-Roaming Routine
One approach toward making the Boe-Bot roam toward light sources is to make it turn away from shade. You can use the ndShade variable to make the BOE Shield-Bot turn a little or a lot when the contrast between the light detected on each side is a little or a lot.
Shady Navigation Decisions
Here is an if statement that works well for turning away from shade on the right side of the BOE Shield-Bot. It starts by declaring two int variables, speedLeft and speedRight. They are not declared within the if…else block because other blocks in the loop function will need to check their values too. Next, if(ndShade > 0.0) has a code block that will be executed if shade is detected on the robot’s right side, slowing down the left wheel to make the BOE Shield-Bot turn away from the dark. To do this, ndShade * 1000.0 is subtracted from 200. Before assigning the result to speedLeft, int(200.0–(ndShade×1000.0) converts the answer from a floating point value back to an integer. We’re doing this to make the value compatible with the maneuver function from Chapter 4, which needs an int value.
int speedLeft, speedRight; // Declare speed variables if (ndShade > 0.0) // Shade on right? { // Slow down left wheel speedLeft = int(200.0 - (ndShade * 1000.0)); speedLeft = constrain(speedLeft, -200, 200); speedRight = 200; // Full speed right wheel }
This diagram shows an example of how this works when ndShade is 0.125. The left wheel slows down because 200 – (0.125×1000) = 75. Since linear speed control is in the 100 to –100 range, it puts the wheel at about ¾ of full speed. Meanwhile, on the other side, speedRight is set to 200 for full speed forward.
The larger ndShade is, the more it subtracts from 200. That’s not a problem in this example, but if ndShade were 0.45, it would try to store –250 in the speedLeft variable. Since the speeds we’ll want to pass to the maneuver function need to be in the -200 to 200 range, we’ll use the Arduino’s constrain function to prevent speedLeft from going out of bounds: speedLeft = constrain(speedLeft, –200, 200).
Here is an else statement that works well for turning away from shade on the left. It slows down the right wheel and keeps the left wheel going full speed forward. Notice that it adds (ndShade*1000) to 200. Reason being, this is the else statement for if(ndShade > 0.0), so it will get used when ndShade is equal to or smaller than zero. So, if ndShade is –0.125, speedRight = int(200.0 + (ndShade * 1000.0)) would evaluate to 200 + (–1.25 × 1000) = 200 – 125 = 75. The constrain function is used again, to limit speedRight.
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 }
Test Navigation Decisions with Serial Monitor
Before actually testing out these navigation decisions, it’s best to take a look at the variable values with the Serial Monitor. So, instead of a call to the maneuver function, first, let’s use some Serial.print calls to see if we got it right.
Serial.print(speedLeft, DEC); // Display speedLeft Serial.print(" "); // Spaces Serial.print(ndShade, DEC); // Display ndShade Serial.print(" "); // More spaces Serial.println(speedRight, DEC); // Display speedRight delay(2000); // 1 second delay }
The print and println calls should result in a display that shows the value of speedLeft in the left column, speedRight in the right column, and ndShade between them. Watch it carefully. The side with brighter light will always display 200 for full-speed-forward, and the other will be slowing down with values less than 200—the darker the shade, the smaller the number.
Example Sketch – Light Seeking Display
- Make sure the power switch is set to 1.
- Enter, save and upload the sketch LightSeekingDisplay.
- Open the Serial Monitor.
- Try casting different levels of shade over the BOE Shield-Bot’s right light sensor. Does speedLeft (in the left column) slow down or even go into reverse with lots of shade?
- Try the same thing with the left light sensor to verify the right wheel slows down.
- Try casting more shade over both. Again, since the shade is the same for both, ndShade should stay close to zero, with little if any slowing of the wheels. (Remember, speedLeft and SpeedRight would have to drop by 100 before they’ll start to slow down.)
/* * Robotics with the BOE Shield - LightSeekingDisplay * Displays speedLeft, ndShade, and speedRight in Serial Monitor. Verifies * that wheel speeds respond correctly to left/right light/shade conditions. */ void setup() // Built-in initialization block { tone(4, 3000, 1000); // Play tone for 1 second delay(1000); // Delay to finish tone Serial.begin(9600); // Set data rate to 9600 bps } void loop() // Main loop auto-repeats { float tLeft = float(rcTime(8)); // Get left light & make float float tRight = float(rcTime(6)); // Get right light & make float float ndShade; // Normalized differential shade ndShade = tRight / (tLeft+tRight) - 0.5; // Calculate it and subtract 0.5 int speedLeft, speedRight; // Declare speed variables if (ndShade > 0.0) // Shade on right? { // Slow down left wheel 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 } Serial.print(speedLeft, DEC); // Display speedLeft Serial.print(" "); // Spaces Serial.print(ndShade, DEC); // Display ndShade Serial.print(" "); // More spaces Serial.println(speedRight, DEC); // Display speedRight delay(1000); // 1 second delay } 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 }