BB2B with wheel encoders

In the first BB2B example, we drove the wheel motors of the roboid directly. When the roboid did not see any obstacle, it should have driving straight forward as both motors were driven with a value of 1. However, in practice, you may see that it actually drives in a big circle because one of the motors was actually turning a bit faster than the other.

This can be fixed with a feed-back loop. A rotation sensor is placed on each wheel measuring how fast the wheel is actually turning. This information is used to adjust the motor speed such that the wheel is turning exactly at the desired speed, resulting in a robot which drives straight forward.

All code for this example is also found in the Roboid Control for Arduino repository as the BB2Bencoder example

Hardware Setup

For this setup, we extend the SwitchesConfiguration build of the BB2B example.

In our example we use optical wheel encoders (to add: photo and description).

To read the optical wheel encoders we use two pulsecounter, one for each motor A and B:

#include "PulseCounter.h"
PulseCounter encoderA = PulseCounter(3, // pinOut, White wire
                                   20 // pulses per full rotation
);
PulseCounter encoderB = PulseCounter(2, // pinOut, White wire
                                   20 // pulses per full rotation
);
You can see that the out pins of the encoders are connected to pin 2 and 3 of the Arduino Uno with white wires. These are actually the only pins which will work on an Arduino Uno, because we are using interrupts to read the pulses coming from the encoder (see Arduino reference: attachInterrupt() for more information about this).
Then we configure a value of 20 as the number of pulses per full rotation. As you may be able to see in the picture above, the disk has 20 holes, which means that when the wheel does a full rotation, 20 holes will pass the sensor and 20 pulses will be generated. So this value ensures that the code knows when the wheel has made a full rotation.

Roboid Setup

The behaviour is very similar to the basic example, but instead of using the DRV8833 motors controller directly, we combine the motor controller and encoders together to create a controlled motor:

ControlledMotor *motorA = new ControlledMotor(&drv8833.motorA, &encoderA);
ControlledMotor *motorB = new ControlledMotor(&drv8833.motorB, &encoderB);  DifferentialDrive *differentialDrive =
new DifferentialDrive(motorA, motorB);
This controlled motor implementation ensures that when the motor target speed is set to a specific value, say 1.0, that the wheel will actually start to turn with speed 1.0.

Roboid Behaviour

So what is this speed 1.0? In the standard BB2B example, a value of 1 meant that the motor should turn as fast as it can. But for an controlled motor, a value of 1 means 1 rotation per second.
With the hardware we use for this example, the motor is actually not able to turn at that speed, being powered with 4.8 volt (4 x 1.2v NiMH batteries) it is not able to overcome the internal resistance of the motors. You may hear a whine making clear that the motor controller is trying to drive  the motor, but it does not move.
Depending on the charge level of the batteries, the minimum speed is about 1.5 revolutions per second, so we need to adjust the motor target speed in the robot behaviour which we will set to 2 revolutions per second:
float leftMotorSpeed = obstacleRight ? -2.0F : 2.0F;
float rightMotorSpeed = obstacleLeft ? -2.0F : 2.0F;
You may also notice that when you change these value to 4.0 that the roboid will not drive twice as fast. It will try to, but its motors simply cannot run at that speed with the given 4.8 volt. Providing a higher voltage (within the limits of the motor controller and the motors of course) may make such speed possible though.
Next to that we also need to talk about the delay(100) at the end of the loop. Normally, it is no problem to decrease this value to increase the update rate of the robot, but if you change this to, for example, delay(10) here, you will see that the robot will not be able to keep its speed very constant.
This is because of the relative low resolution of the wheel encoders. With 20 holes, the pulse counter can see 40 changes per revolution at maximum: per hole we have 2 transitions: 1 from blocked to open and 1 from open to blocked. When the wheel is turning at 2 rotations per second, it will therefore see about 80 transitions per second. If we now run the script with delay(10) we try to determine the speed about 100 times per second. The result of this is that per update, the encoder sees only 1 or 0 transitions (100 updates / 80 transitions per second = 0.8 transitions per update). This is clearly not enough to measure the wheel speed very accurately. So we either have to slow down the update rate or use an optical encode with more holes, increasing the number of transitions per revolution.