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"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).
PulseCounter encoderA = PulseCounter(3, // pinOut, White wire
20 // pulses per full rotation
);
PulseCounter encoderB = PulseCounter(2, // pinOut, White wire
20 // pulses per 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);
Roboid Behaviour
float leftMotorSpeed = obstacleRight ? -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.
float rightMotorSpeed = obstacleLeft ? -2.0F : 2.0F;