lechw3-add-I-friction
Lecture Assignment 3: Added Inertia and Friction to System
Overview:
In this assignment we add friction and then inertia to the motor system. We gather experimental data and use this to update the simulation parameters so the simulation matches the experimental results.
Add motor driver and filter velocity: Repeat the last HW assignment of running the motor without anything attached, but this time:
Use motor driver to to turn motor on at 100% duty cycle.
Use the provided interrupt code to measure the encoder position reliably.
Use the timing of Arduino commands to estimate the maximum speed you can read the encoder while outputting the time and counts before you need an interrupt.
Plot the motor velocity vs time for 200 msec
Use the Matlab smooth command (new link!) to remove noise in the velocity. Use "hold on" to keep the raw velocity and add plots of:
Increase the span to the point where you over smooth the data.
Select an appropriate span number and plot the well smoothed velocity.
Discuss what is the problem of over smoothing the data and how you selected your final smoothing span.
Use a 1st order low pass filter implemented in the time domain to remove noise from the velocity. Use the filtering equation in Time Domain (new link!) since this is what you would need to implement in real-time control. Use "hold on" to keep the raw velocity and add plots of:
Increase the filtering to the point where you over filter the data.
Select an appropriate filter and plot the well filtered velocity.
Discuss what is the problem of over filtering the data and how you selected your final filtering parameters.
Discuss how using the motor driver differs from directly driving the motor from the 12 VDC power supply.
Add Potentiometer and measure the friction.
Connect the pot to an analog input and include analog input into your Arduino code to measure both the pot and encoder position.
Mount the pot with a 1" flexible shaft coupling (Tygon tubing) between the pot and motor. Operate the motor at 100% duty cycle and measure the terminal velocity. Then operate the motor back and forth at 100% duty for 100 milliseconds each direction.
Use the motor torque-speed curve to derive the algebraic relationship between terminal velocity and friction in the system, i.e.
πfriction = function( πterminal , πnoload , πstall )
Use the equation to determine the friction in the system and compare this to the friction in the pot spec sheet.
Create a plot based upon the pot position and the encoder position to show if there is any lag or slip in the system due to the flexible shaft coupling.
Repeat the above the test with as short a flexible shaft coupling as possible. Discuss the results.
Select a good length for the coupling based upon a tradeoff between friction and lag. Discuss your approach.
Add the measured friction to your Matlab simulation code, and plot the measured velocity vs your new simulation. Discuss the results.
Add Small Inertia Wheel and Measure the Acceleration.
Remove the pot and mount the 6" shaft with small inertia wheel (no bolts). use your desired length of flexible shaft coupling from the prior step.
Operate the motor at 100% duty cycle for 200 milliseconds.
Estimate the acceleration using the initial slope of the velocity curve. A suggested method is using least squares on the initial portion of the data.
Add bolts onto the inertia wheel and repeat the above step.
Use the data from these 2 tests to estimate the inertia of your motor.
Update the inertia in your simulation and compare the simulated velocity to the measured velocity. Discuss.
Interrupt Code
/*
* MAE 156A - Interrupt Function for Measuring No-Load Speed
* Motor: Pololu Motor 3260
* Spec No-Load Speed: 5600 RPM
*
* September 29th, 2016
*
*/
#define motor_pwm 3 //define PWM pin number for motor pwm
#define motor_dir 12 //define digital pin number for motor direction
int encA = 2; //define Encoder A channel pin
int encAnow = LOW; //define current state of Encoder A
int encAprev = LOW; //define previous state of Encoder A
unsigned long t, count; //interrupt timing and counting variables
void setup() {
Serial.begin(115200); //serial output transmission rate (bps)
pinMode(encA, INPUT); //Encoder A on motor encoder
// Using the interrupt on Digital Pin #2
attachInterrupt(digitalPinToInterrupt(encA),encoder,CHANGE);
pinMode(motor_dir, OUTPUT); //define Pin 12 for motor direction (HIGH or LOW)
digitalWrite(motor_dir, HIGH); //set motor direction
analogWrite(motor_pwm, 255); //set motor speed in duty cycle (0-255)
}
void loop() {
Serial.print(micros()); //time base for speed data
Serial.print(","); //data separator character
Serial.println(count); //counts for position and velocity calculation
}
void encoder() { //interrupt handler code
encAnow = digitalRead(encA); //read the current state of Encoder A
// Check if Encoder A is transitioning from 'LOW' to 'HIGH' State
if ((encAprev == LOW) && (encAnow == HIGH)) {
count++; //increase the number of Encoder A count
}
encAprev = encAnow; //set the previous Encoder A reading as same as the current reading
}