Lab 4: Motors and Open Loop Control
Lab 4: Motors and Open Loop Control
In this lab, we work on controlling the robot, Meep, with open-loop pwm signals. We start by soldering the motor driver and testing the pwm signal generated via analogWrite. Meep has two motors and operates on differential drive.
Wire Set Up
Full Circuit Diagram
To start, this lab involves soldering the final componenets needed to assemble Meep. The circuit diagram below shows all the connections and GPIOs used by Meep. I chose to use the 850 mAh battery to power both the motors since I wanted to just have two batteries in the robot (one to power the Artemis and one to power both the motors). The 850 mAh battery should be able to handle the current draw without depleting too quickly.
I assembled the bot as shown below. I placed the IMU on a flat service and secured it by drilling holes and putting in zipties (idea from Shao Stassen). The ToF is secured with orange tape in this photo, but will be secured with a piece of double sided tape in the near future. Since it is important the ToFs are facing straight, I made sure to secure them onto a flat surface. The Artemis faces with the bluetooth antenna facing outward in the hope of minizing EMI interference with the bluetooth. The motor drivers are placed on either wall on either side of the Artemis, keeping the wires short. I also expanded the hole that the battery wire comes through to store the Artemis battery with the motor battery on the other side of the bot.
Motor drivers
I started by soldering by motor drivers.
I decided to connect the motor drivers to A14, A15, A2, and A3. I did this for serval reasons:
-
I wanted each motor drivers to be on analog pins since that would be the most compatiable with the analogWrite command used to generate the PWM signals.
-
We needed to choose pins that can generate a pwm signal. By looking at the datasheet, we can see that pins with a tilde (~) can generate pwm signals.
- Since the wires to connect to the motors are on opposite sides of the bot, I chose pins that were on opposites sides of the Artemis. I wanted the wires to avoid crossing eachother and be as short as possible to reduce possible electromagnetic interference (EMI).
PWM and Oscilloscope
Power Supply Settings
I set my power supply to 3.70 V since I planned to use the 850 mAH lipo which has a nominal voltage of 3.7 V. I set the max current to 2 A so that the driver could run without tripping the power supply. After soldering the motor drivers to the Artemis, I generated a PWM signal with analogWrite and probed them as shown below.
#define AB2_left 2
#define AB1_left 3
#define AB2_right 14
#define AB1_right 15
Serial.begin(115200);
pinMode(AB1_left,OUTPUT);
pinMode(AB2_left,OUTPUT);
pinMode(AB1_right,OUTPUT);
pinMode(AB2_right,OUTPUT);
analogWrite(AB1_left,0);
analogWrite(AB2_left,60);
analogWrite(AB1_right,60);
analogWrite(AB2_right,0);
PWM, or pulse width modulation, is frequently used to control motor speeds. The PWM has a duty cycle, or a percentage of time when the signal is set to high. By lowering the duty cycle, the average voltage that the motor sees decreases, causing the motors to have a lower rpm. An example of the readings for 25%, 33%, 50%, and 100% duty cycle are shown below.
Testing Drive
I started with testing each side individually by connecting the driver I was testing to the power supply. Note that the code that is running is listed under the Power Supply Settings section.
Then, I connected the VINs and Grounds together and ran both motors.
Lowest PWM
To find the lowest PWM that Meep will move from rest with, I started with loop code that would try to drive forward at a set PWM for 3 seconds, then increase the pulse width by one. The robot started moving in the 35-39 range. I tested individual pulse widths from there till the robot began to move at 37 or 14.5% duty cycle.
void loop() {
forward(pwm); // Or left(pwm) depedning on which we want to control
// SEND ANYTHING ACROSS THE SERIAL PORT TO STOP THE BOT
if (Serial.available() > 0){
a = Serial.readString();
Serial.println("COMMAND TO WAIT SENT");
wait = 1;
while(wait){
if (!Serial.available() > 0){
// Serial.println("Waiting");
stop();
}
// RESTART WITH NEW PWM WHEN SENT A NEW MESSAGE
else {
Serial.println("Reading");
pwm = Serial.parseInt();
wait = 0;
Serial.print("PWM IS NOW: ");
Serial.println(pwm);
}
}
Serial.println("COMMAND TO CONTINUE SENT");
while (Serial.available() > 0) {
Serial.read(); // Clear Serial Input so we dont end up waiting
}
}
}
For turning, the robot started moving at 93 with very jittery motion.
We see that the turning is more smooth starting at 100. It is good to note that turning requires a higher duty cycle than simple forward motion since there is more friction working against turning the wheels than just moving forward/backward in the direction the wheels are already facing.
Tuning the straight drive
To test how straight my robot drove, I ran both motors with 60 (23.5% duty cycle) for 6ft. Without calibration, Meep naturally drifted to the left.
To fix this, I simply slowly lowered the right pwm so that the robot would stay on course. This fixed the straight drive as demonstrated in the video below.
ble.send_command(CMD.FORWARD, "55|60") case FORWARD: {
int flspeed, frspeed;
success = robot_cmd.get_next_value(flspeed);
if (!success)
return;
success = robot_cmd.get_next_value(frspeed);
if (!success)
return;
analogWrite(AB1_left,0);
analogWrite(AB2_left,flspeed);
analogWrite(AB2_right,0);
analogWrite(AB1_right,frspeed);
// Added so I can record the straight drive without the robot running away
delay(4000);
analogWrite(AB1_left,0);
analogWrite(AB2_left,0);
analogWrite(AB1_right,0);
analogWrite(AB2_right,0);
//////////////////////////////////////
break;
}
Open Loop Robot Control
I ran open loop control with the robot to try to get it to head towards a wall and turn before it hit it. I did this with manual motion commands. This would be much easier to do with closed loop control. Meep would be able to use the time of flight sensor to tell when to turn and use the IMU to determine how much to turn by. We will be exploring this concept in the next lap.
Grad Tasks
5000: Analog Write
We can see from the PWM oscilloscope reading that period of the pwm signal is 5.460 ms. Using this, we can calculate the frquency to be 1/0.005460 or 183.15 Hz.
void forward(int ls, int rs) {
analogWrite(AB1_left,ls);
analogWrite(AB2_left,0);
analogWrite(AB1_right,0);
analogWrite(AB2_right,rs);
}
void loop(){
for (i = 1; i <5; i++){
forward(255/i, 255/i);
delay(1000);
}
}5000: Lowest PWM with Motion
I found the lowest PWM that kept the bot in motion by lowering the PWM one by one until the bot stopped movement. The bot stopped moving at 44 which is odd since this is higher than the pwm needed to get it to move from rest. Upon rerunning my moving the vehicle from rest, I got a similar result as prior. I would expect this PWM to be lower since it takes less force to keep the bot in motion when it already has inertia in the direction we are trying to move.
Collaboration and Sources
I collobrated with Dyllan and Shao on bot building ideas. I referenced Aiden Derocher’s and Tyler Wisniewski’s lab reports when building my robot.