I transitioned my RC car from manual control to open loop control by integrating a SparkFun RedBoard Artemis Nano with dual motor drivers.
Having used digital pin 2 in the previous lab, I opted for digital pins 0, 1, 3, and 5 in this experiment since they all support PWM via the analogWrite()
function. I connected each of these pins to an input on the motor driver using parallel-coupling to deliver twice the average current without overheating the chip. Similarly, the outputs were parallelly coupled to the positive and negative terminals of each motor for the respective motor driver. Finally, I tied together the grounds of the 3.7 V batteries, the Artemis, and the motor drivers, and connected the VIN pins of both motor drivers to the positive terminal of one of the batteries.
I powered the Artemis and the motor drivers/motors from separate batteries because the motors draw high currents and create electrical noise that can disturb the sensitive electronics on the Artemis.
Following the wiring diagram I created, I connected the first motor driver to pins 0 and 1 on the Artemis and tied the grounds of the Artemis and the motor driver together.
To verify the functionality of the motor driver before integrating it into the RC car, I used a power supply to deliver 3.7 volts through the VIN pin as it replicates the battery’s voltage. I then measured the output from pin 0 using an oscilloscope and the code below.
#define PWM_0 0
int i = 0;
void setup() {
pinMode(PWM_0, OUTPUT);
analogWrite(PWM_0, 0);
}
void loop() {
analogWrite(PWM_0, i);
delay(100);
i = (i + 10) % 255;
}
This is the result on the oscilloscope.
In order to modify the RC car to my specifications, I began by disassembling it and removing most of the original components. I carefully removed all the screws, storing them securely, and then detached the outer blue shell. Once opened, I found a PCB populated with connected LEDs and wires. I removed the PCB by cutting the wires as close as possible to preserve their maximum length for future use. With these components removed, I was left with a blank canvas with which to work.
After verifying the motor driver’s functionality with the oscilloscope, transitioning to using it to drive the motor was straightforward. I followed the wiring diagram and connected the outputs to the respective positive and negative leads of the motor.
The next step involved developing the code shown below to drive the wheels in both clockwise and counterclockwise directions.
#define PWM_0 0
#define PWM_1 1
void setup() {
pinMode(PWM_0, OUTPUT);
pinMode(PWM_1, OUTPUT);
}
void loop() {
// Drive motor clockwise:
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 128);
delay(5000); // Run for 5 seconds
// Stop motor:
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
delay(5000); // Pause for 5 seconds
// Drive motor counterclockwise:
analogWrite(PWM_0, 128);
analogWrite(PWM_1, 0);
delay(5000); // Run for 5 seconds
// Stop motor:
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
delay(5000); // Pause for 5 seconds
}
The result is the following demonstration of the wheels spinning, powered still by the 3.7 V from the external power supply.
The only change from the previous task was replacing the external power supply with an 850mAh battery (3.7 V). To achieve this, I stripped the wire connected to the JST connector for the battery, as well as the VIN and GND wires for the motor driver, and joined them using electrical tape instead of soldering. This approach was chosen to facilitate an easier extension to the other motor driver in the next task. This results in the below display.
To drive both sets of wheels, I connected the outputs of the second motor driver to the second motor and soldered the VIN and GND connections of both motor drivers to the battery’s JST connector. I then used the updated code below to run both sets of wheels.
#define PWM_0 0
#define PWM_1 1
#define PWM_3 3
#define PWM_5 5
void setup() {
pinMode(PWM_0, OUTPUT);
pinMode(PWM_1, OUTPUT);
pinMode(PWM_3, OUTPUT);
pinMode(PWM_5, OUTPUT);
}
void loop() {
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 128);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 128);
delay(5000);
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 0);
delay(5000);
analogWrite(PWM_0, 128);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 128);
analogWrite(PWM_5, 0);
delay(5000);
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 0);
delay(5000);
}
The result is the following demonstration of the of all the wheels spinning, powered by the battery.
I then created a Bluetooth command to remotely control the car, providing a convenient way to test its driving performance.
case DRIVE_TEST: {
analogWrite(PWM_0, 128);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 128);
delay(3000);
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 0);
break;
}
To test the lower limit of the PWM values, I developed a new Bluetooth command that sends the desired PWM values to each pin using the analogWrite() function.
case SEND_PWM_VALUE: {
int pwm_a, pwm_b, pwm_c, pwm_d;
// Extract the next value from the command string as an integer
success = robot_cmd.get_next_value(pwm_a);
if (!success)
return;
// Extract the next value from the command string as an integer
success = robot_cmd.get_next_value(pwm_b);
if (!success)
return;
// Extract the next value from the command string as an integer
success = robot_cmd.get_next_value(pwm_c);
if (!success)
return;
// Extract the next value from the command string as an integer
success = robot_cmd.get_next_value(pwm_d);
if (!success)
return;
analogWrite(PWM_0, pwm_a);
analogWrite(PWM_1, pwm_c);
analogWrite(PWM_3, pwm_d);
analogWrite(PWM_5, pwm_b);
delay(3000);
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 0);
break;
}
I found that a PWM value of approximately 45 is the minimum threshold for the car to start moving forward, while a value of 120 is required for it to begin turning on its axis.
Calibrating with the SEND_PWM_VALUE
command, I discovered that setting the right motor to 98 and the left motor to 128 produces a relatively straight line. This indicates a calibration factor of approximately 1.31 from right to left and, conversely, about 0.77 from left to right.
I finally developed an open-loop command to evaluate the overall performance of my RC car by driving it straight and executing turns.
case OPEN_LOOP: {
analogWrite(PWM_0, 70);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 70);
delay(3000);
analogWrite(PWM_0, 128);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 128);
analogWrite(PWM_5, 0);
delay(3000);
analogWrite(PWM_0, 128);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 70);
analogWrite(PWM_5, 0);
delay(3000);
analogWrite(PWM_0, 128);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 128);
analogWrite(PWM_5, 0);
delay(3000);
analogWrite(PWM_0, 0);
analogWrite(PWM_1, 0);
analogWrite(PWM_3, 0);
analogWrite(PWM_5, 0);
break;
}
This lab taught me the importance of precise wiring when working with microcontrollers. The lab provided valuable hands-on experience in motor control and system calibration, laying the groundwork for future closed-loop control enhancements.