Beruflich Dokumente
Kultur Dokumente
ACTS
I. System Summary and Placement II. Analog Front End III. Power System IV. Steering Control System V. Motor Control System VI. Servo Control System VII. Chassis Assembly VIII.Microcontroller Engineering a. Analog-To-Digital Converter b. Timer/Counter and PWM IX. Programming X. Team Lead XI. APPENDIX: CODE (Finale)
We chose to implement the sensor system by inductively sensing the track. The main reason for this (as opposed to an optical sensor system) is that it ensured us that we would not have to worry about setting up a specific type track every time we wanted to test the car. Sensing the track inductively allowed us to design our system knowing the exact frequency that we were working with, and thus simplified the design and test process. The LC tank, mounted on the front end of the car, senses the 75 kHz, 100 mA (rms) current running through the natcar track wire. That signal is then amplified and rectified; the peak is detected, and then filtered in order to remove the ripple from the resistor-capacitor setup of the peak detector. The output is then sent to the microcontroller for use in the control system. The scheme is basic for a natcar design, with each op-amp powered by a positive and negative five volt power supply. There are three total sensors used, one placed in the middle of the front of the car, and one on each of the front left and front right side. The circuit diagrams we used for each block are shown here:
AFE: Issues Encountered The main issue we encountered with the AFE was hardware issues. For the initial prototype, we used solderless breadboards to build all of the circuits, but we quickly and frequently had problems with loose connections, short circuits, and other problems caused by spacing and the inability to access different areas of the circuits for debugging. This issue was solved by changing to perfboards for all circuits, and significantly reducing the space used by all of the systems. We placed the entire sensor signal processing system onto a single perfboard and placed it on one side of the car, and the motor and power system on another perfboard mounted on the opposite side of the car. This granted us easy access to any system for debugging purposes, and the soldered connections significantly
reduced hardware errors in the later weeks of the project, giving us the ability to focus on the software. The second error we encountered was amplification of the signal received from the LC tank. It became obvious that our coil response was affected by outside sources of noise when we tested the sensors in certain area; therefore, we had to make sure to recalibrate the amplifier gain every time we did test runs of the car. Because the sensors were designed so that we could fine tune the gain of the amplifier, we were sometimes unable to obtain the full voltage range that the microcontroller expected from the sensor system. Thus, we had to be aware of the location in which we tested our car.
The batterys voltage output was used as the input for the LM350 (positive 5 volt regulator), as well as the power for the servo and the H-bridge. Power System Issues Encountered We chose regulators built specifically to output the voltage we needed rather than adjustable regulators (except for the LM350). This saved us the trouble of finding exact resistor values to obtain the voltages we needed. The only real issues we faced in building the power system were spacing problems. Because every regulator required stabilizing capacitors, it was difficult to minimize the space required for the power system. We ended up solving this problem by grounding all the capacitors together and raising them above the regulators. This gave us the ability to place the H-Bridge and the power system on the same board.
The dynamic behavior of the car was derived by several different natcar reports online. Therefore we will only include the transfer functions of the different systems affecting steering: Transfer function (car):
Where
Where
We have assumed that the sensors provide an output proportional to the error. The control loop is shown as:
Where
Our initial design included only proportional control, and a simple simulation in Matlab gives us the step response for a proportional gain of one:
As we can see, there is overshoot in the system and the response is slow. Including integral and derivative terms in the controller, we obtain the step response:
Clearly, the cars response is much faster (note the x-axis time scale), and so we see that the integral and derivative terms are necessary. With this in mind, we tuned the controller based on the cars actual performance on the track, since the simulation is limited in what it actually demonstrates about car performance. Matlab Code: %Natcar PID controller - steering L = 0.3; % wheelbase (m) L_prime = 0.35; % back tire to sensor array (m) v = 1.524; % car velocity (m/s) K_phi = pi/2; % servo gain Ks = 1; % deviation from track (propotionality constant) w_phi = (pi/3)/(0.03); % servo bandwidth Hcar_num = [L_prime*v v^2]; Hcar_den = [L 0 0]; Hservo_num = K_phi; Hservo_den = [1/w_phi 1]; Hp_num = conv(Hcar_num,Hservo_num); Hp_den = conv(Hcar_den,Hservo_den); sysHp = tf(Hp_num,Hp_den);
Kp = 1.2; Kd = 4; Ki = 0.04; Hc_num = [Kd Kp Ki]; Hc_den = [1 0]; sysHc = tf(Hc_num,Hc_den); sysHs = tf(Ks,1); sysTCL = 1/(1+sysHs*sysHc*sysHp); step(sysTCL, 0.3); title('Step Response: Kp = 1.2, Kd = 4, Ki = 0.04'); figure;rlocus(sysTCL);
Node A is tied to the microcontrollers forward port. Providing a 3.3 V PWM to this node would determine the duty cycle and speed of the car in the forward direction. If the signal at Node A is high, Q1 will turn on, resulting in Q2, Q3, and Q4 also turning on and providing current flow through the motor and vice versa if the signal is low. Node B is tied to the microcontrollers reverse port. Providing a 3.3 V PWM to this node would determine the duty cycle and speed of the car in the reverse direction. If the signal is high at Node B, Q5 will turn on, resulting in Q6, Q7, and Q8 also turning on and providing current flow through the motor in the other direction. The four diodes are installed for protection against back EMF. Currently, the cars code only utilizes the forward direction. Reverse direction, meant to be used as a braking feature, has not been implemented yet for the sake of simplicity.
The resistor value was chosen to provide an adequate current to the servo. The servos pulse width is from 0.9 ms to 2.1 ms while the pulse period is 20 ms. Thus, a PWM signal with 0.9/20 duty cycle would result in the car steering left, while a signal with 2.1/20 duty signal will steer right. However, since the common emitter NPN amp inverts the signal it receives, it is necessary to invert the signal that the microcontroller outputs. The amp would invert this inverted signal to output our intended servo control signal.
VII.
Chassis Assembly
Our chassis design goal was to be as minimalistic as possible. Following this vision, we condensed all circuitry into two 1.2 x 3.0 solderable PC breadboards. Robust soldering work reinforced most of our connections and wiring systems. This solved all our electrical issues in terms of unpredictability and malfunction, dramatically reducing the need to debug hardware problems. We placed one on each side of the car in order to achieve optimal weight balance and center of gravity. We also stiffened the front suspension for handling improvement, since suspension is not necessary for the terrain we were facing. Overall, aesthetic value was improved while minimizing weight.
B. Timer/Counter and Pulse Width Modulation The Xplained board has multiple clock sources. There are four main internal oscillators. 32KHz, 32.768KHz, 32MHz, and 2MHz. For our project, the timer played a crucial role in clocking the instruction set, counter, and analog-to-digital converter. We experimented with the latter three clock sources and found the 2MHz oscillator to fit best with our needs. We discussed using the 32Mhz clock, and found the oscillations have more instability, which has the risk to jeopardize some of the values from the ADC.
The Xmega has the built-in ability to output pulse width modulated signals. It can use any of the Timers/Counters available. Our design used PWM in order to align the servo motor and power the rear drivetrain motor. We were able to vary the signal output by making adjustments to the comparing value (TOP) on the Timer/Counter as the figure below shows.
IX. Programming
Our main Natcar code is well commented, so navigating the program is rather selfexplanatory. The final project code is included in the Appendix. The barebones skeleton of the programs function can be seen below in pseudocode. main() drive rear motor while(always) { read in values from sensors take a moving average of sensor values //use sensor data to manipulate steering offset value Calculate proportional offset Calculate integral offset Calculate derivative offset Use offset value to change the pulse width signal outputted }
X. Team Lead
Initially our group shared hesitation in which project, Natcar or Micromouse, would suit our team best. We wanted a challenge, but not to get in over our heads. We decided on Natcar, and I volunteered to be Team Lead and take on any extra responsibility and milestone management. I really enjoy being in a leadership role, especially when working with competent engineers such as David and Isaac. As a leader, I cannot say I did anything Isaac or David wouldnt have done. We worked quite seamlessly as a group. In fact, I believe our small number was the reason we made the rapid progress we did. Isaac, David and I were able to collaborate more as a team, and were dependent on helping each other to make progress. By the nature of the project, most of our progress came in bursts. We would spend half days in the lab to get as much done as we could, and then a few days off to work on other classes. Part of the role I initially assumed was dissemination of Natcar related information, whether it be part specs, design ideas, or video tutorials. It was also my pleasure in maintaining well documented progress for milestone goals, Gantt chart, and photo journal. Overall, I think our group managed the deadlines well and were very efficient with our time together.
#define servo's #define #define #define the PWM #define motor #define average #define for the #define
centerValue 3700 // The value callibrated to the center (straight) point leftValue 3630 // The left bound to the servo rightValue 3770 // The right bound to the servo motorSpeed 11500 // The compare value to generate for the rear motor CounterPeriod 40000 // The freqency value for the rear MovingAverage 4 Threshold sensor inputs integrealMin 0 200 // The number of input values to // The estimated threshold // Integreal lower bounds
#define integrealMax
120
static int16_t ADC_resultLeft[MovingAverage], ADC_resultRight[MovingAverage], ADC_resultMid[MovingAverage]; static uint16_t averageLeft, averageRight, averageMid; struct {float left; float mid; float right;} PrevSensorData; struct {float left; float mid; float right;} sensorData;
void driveMotor(void) { TC_SetPeriod(&MotorTimer, CounterPeriod); TC_SetCompareA(&MotorTimer, motorSpeed); //COnfigure the clock frequency TC1_ConfigClockSource(&MotorTimer, TC_CLKSEL_DIV1_gc); } void stopMotor(void) { TC_SetPeriod(&MotorTimer, CounterPeriod); TC_SetCompareA(&MotorTimer, 0); //COnfigure the clock frequency TC1_ConfigClockSource(&MotorTimer, TC_CLKSEL_DIV1_gc); } void SetServo(uint16_t offset) { TC_SetCompareA(&ServoTimer, offset * 10); //COnfigure the clock frequency TC0_ConfigClockSource(&ServoTimer, TC_CLKSEL_DIV1_gc); } int main(void) { uint16_t i; bool motorBool; uint16_t ServoOffset; uint16_t PrevServoOffset; float proportionalGain, derivativeGain, integralGain; proportionalGain = 0.8;
derivativeGain = 0; integralGain = 0.002; PrevServoOffset = centerValue; float integralError; float derivativeError; integralError = 0; derivativeError = 0; PrevSensorData.right PrevSensorData.left PrevSensorData.mid = 0; = 0; = 0;
// Set as output and turn off the LEDs as default LEDPORT.DIR = 0xFF; //Set as ouput, the 8 MSB of the result is output here LEDPORT.OUT = 0xFF; //Default off for LED PSWITCH.PIN0CTRL=PORT_OPC_PULLUP_gc; PSWITCH.DIR = 0X00; motorBool = false; //***************************************************** // Power On Self Test // //***************************************************** for(i = 65535; i > 0; i--) { LEDPORT.OUT = 0x00; } LEDPORT.OUT = 0xFF; //Default off for LED //***************************************************** // Set up PWM for motor/servo // //***************************************************** //Set the CC Mode ServoTimer.CTRLB = TC_WGMODE_SS_gc; MotorTimer.CTRLB = TC_WGMODE_SS_gc; //Prepare the WG output pins (servo pin 0) (motor pin 4) ServoTimer.CTRLB |= TC0_CCAEN_bm; MotorTimer.CTRLB |= TC1_CCAEN_bm; PWPORT.DIRSET = PIN0_bm | PIN4_bm; //Set the period on the servo
TC_SetPeriod(&ServoTimer, CounterPeriod); //Set the compare value for the motor TC_SetCompareA(&MotorTimer, 0); //Set the servo to the center ServoOffset = centerValue; // Center SetServo(ServoOffset); //***************************************************** // Initialize ADC // //***************************************************** // Move stored calibration values to ADC A. ADC_CalibrationValues_Load(&AnaDigaC); // Set up ADC A to have unsigned conversion mode and a 8 bit resolution ADC_ConvMode_and_Resolution_Config(&AnaDigaC, ADC_ConvMode_Signed, ADC_RESOLUTION_12BIT_gc); // Sample rate ADC_Prescaler_Config(&AnaDigaC, ADC_PRESCALER_DIV32_gc); // Set reference voltage on ADCx to be external - pin 0 ADC_Reference_Config(&AnaDigaC, ADC_REFSEL_AREFA_gc); // Setup channel 0 to have differential input ADC_Ch_InputMode_and_Gain_Config(&AnaDigaC.CH0, ADC_CH_INPUTMODE_DIFF_gc, ADC_CH_GAIN_1X_gc);//ADC_CH_INPUTMODE_SINGLEENDED_gc ADC_Ch_InputMode_and_Gain_Config(&AnaDigaC.CH1, ADC_CH_INPUTMODE_DIFF_gc, ADC_CH_GAIN_1X_gc); ADC_Ch_InputMode_and_Gain_Config(&AnaDigaC.CH2, ADC_CH_INPUTMODE_DIFF_gc, ADC_CH_GAIN_1X_gc); // Set positive input to the channels 6),2(MIDDLE - 4) in ADCA (GND - 1) ADC_Ch_InputMux_Config(&AnaDigaC.CH0, ADC_CH_MUXNEG_PIN1_gc); ADC_Ch_InputMux_Config(&AnaDigaC.CH1, ADC_CH_MUXNEG_PIN1_gc); ADC_Ch_InputMux_Config(&AnaDigaC.CH2, ADC_CH_MUXNEG_PIN1_gc); // Enable ADC A ADC_Enable(&AnaDigaC); // Wait until common mode voltage is stable. Clock is 2MHz and // therefore below the maximum frequency to use this function. 0(LEFT - 2),1(RIGHT ADC_CH_MUXPOS_PIN2_gc, ADC_CH_MUXPOS_PIN6_gc, ADC_CH_MUXPOS_PIN4_gc,
ADC_Wait_8MHz(&AnaDigaC); //Set the ADC start flag to free running mode //ADC_FreeRunning_Enable(&AnaDigaC); PrevSensorData.right PrevSensorData.left PrevSensorData.mid while(1){ ServoOffset = centerValue; derivativeError = 0; //***************************************************** // Button // // This is the push button which operates the rear motor //***************************************************** if (!PSWITCH.IN) { if(motorBool){ stopMotor(); } else{ driveMotor(); } motorBool = !motorBool; } averageRight = 0; averageLeft = 0; averageMid = 0; i = MovingAverage; //***************************************************** // Moving Average from ADC Inputs //***************************************************** do { // Start Conversion ADC_Ch_Conversion_Start(&AnaDigaC.CH0); ADC_Ch_Conversion_Start(&AnaDigaC.CH1); ADC_Ch_Conversion_Start(&AnaDigaC.CH2); // Wait for conversion to finish while(!ADC_Ch_Conversion_Complete(&AnaDigaC.CH0)); while(!ADC_Ch_Conversion_Complete(&AnaDigaC.CH1)); = Threshold; = Threshold; = Threshold;
while(!ADC_Ch_Conversion_Complete(&AnaDigaC.CH2)); // ADC_ResultCh_GetWord returns a signed 2 byte value ADC_resultRight[i-1] = ADC_ResultCh_GetWord(&AnaDigaC.CH1); ADC_resultLeft[i-1] = ADC_ResultCh_GetWord(&AnaDigaC.CH0); ADC_resultMid[i-1] = ADC_ResultCh_GetWord(&AnaDigaC.CH2); // Check and correct negative values if (ADC_resultRight[i-1] < 0) ADC_resultRight[i-1] = 0x0000; if (ADC_resultLeft[i-1] < 0) ADC_resultLeft[i-1] = 0x0000; if (ADC_resultMid[i-1] < 0) ADC_resultMid[i-1] = 0x0000; // Calculate running total to be used for average averageRight+= (uint16_t) ADC_resultRight[i-1]; averageLeft += (uint16_t) ADC_resultLeft[i-1]; averageMid += (uint16_t) ADC_resultMid[i-1]; --i; }while(i > 0); // Average the values to compensate for noise sensorData.right = averageRight / MovingAverage; sensorData.left = averageLeft / MovingAverage; sensorData.mid = averageMid / MovingAverage; //****************************************** // P Controller // //****************************************** // Set the ServoOffset value proportionally with the sensor input // the value of the denominator is to divide the 2048mv range to equal segments ServoOffset += proportionalGain * (sensorData.right/1900) * (rightValue - centerValue); ServoOffset -= proportionalGain * (sensorData.left/1900) * (centerValue - leftValue);
//****************************************** // I Controller // //****************************************** integralError +=(sensorData.right - sensorData.left); if (integralError < integrealMin) integralError = integrealMin; else if (integralError > integrealMax) integralError = integrealMax; ServoOffset += integralGain*integralError; //****************************************** // D Controller // //****************************************** derivativeError = ServoOffset - PrevServoOffset; ServoOffset += derivativeGain*derivativeError; //***************************************************** // Check for Extremes // // THis section of code is used to check for extreme values // of the natcar position, i.e., if the car looses the track // it should remaing turned in the last position as to return // to the track, or if the car approaches a stair step it should // turn to the extremem bounds, left or right, to follow the line. //***************************************************** if (sensorData.mid > sensorData.left && sensorData.right > sensorData.mid && sensorData.mid < Threshold) { ServoOffset = rightValue; } else if (sensorData.mid > sensorData.right && sensorData.left > sensorData.mid && sensorData.mid < Threshold) { ServoOffset = leftValue;
} if (sensorData.mid < Threshold && ((PrevSensorData.right > sensorData.right) || sensorData.right < Threshold) && PrevServoOffset > centerValue) { ServoOffset = PrevServoOffset; } else if (sensorData.mid < Threshold && ((PrevSensorData.left > sensorData.left) || sensorData.left < Threshold) && PrevServoOffset < centerValue) { ServoOffset = PrevServoOffset; } //****************************************** // Steer // //****************************************** // Preserve the sensor data PrevSensorData.right = sensorData.right; PrevSensorData.left = sensorData.left; PrevSensorData.mid = sensorData.mid; // Check the error bounds on the ServoOffset if(ServoOffset < leftValue) ServoOffset = leftValue; if(ServoOffset > rightValue) ServoOffset = rightValue; // Set the servo value to ServoOffset SetServo(ServoOffset); //Preserve the servo offset for next iteration PrevServoOffset = ServoOffset; } }