+ All Categories
Home > Documents > Ping Pong Bong Final Paper 080319 3

Ping Pong Bong Final Paper 080319 3

Date post: 10-Apr-2015
Category:
Upload: api-3767208
View: 232 times
Download: 1 times
Share this document with a friend
33
Ping Pong Bong Marcus Gibson Christopher Thomas MECH 208 Final Project Paper March 10, 2008
Transcript
Page 1: Ping Pong Bong Final Paper 080319 3

Ping Pong Bong

Marcus GibsonChristopher Thomas

MECH 208Final Project Paper

March 10, 2008

Page 2: Ping Pong Bong Final Paper 080319 3

Table of Contents

1 Synopsis.......................................................................................................................12 Design Description......................................................................................................1

2.1 Tube.....................................................................................................................42.2 Sensor..................................................................................................................4

2.2.1 Photo............................................................................................................42.2.2 Specification Sheet......................................................................................52.2.3 Calibration...................................................................................................62.2.4 Dynamics.....................................................................................................6

2.3 Actuator...............................................................................................................82.3.1 Photo............................................................................................................82.3.2 Specification Sheet......................................................................................82.3.3 Calibration...................................................................................................82.3.4 Dynamics.....................................................................................................9

2.4 Microcontroller..................................................................................................102.5 Motor Driver......................................................................................................11

2.5.1 Photo..........................................................................................................112.5.2 Specification Sheet....................................................................................11

2.6 Software Design.................................................................................................122.6.1 Software Flowchart....................................................................................12

2.7 Overall Schematic..............................................................................................132.8 Overall Configuration Labeled Photo................................................................14

3 Control System Design..............................................................................................153.1 Simulation..........................................................................................................153.2 Experimental Performance Comparison............................................................163.3 Results and Discussion......................................................................................16

3.3.1 Sensor Noise..............................................................................................163.3.2 Integral Control..........................................................................................17

A. Software Code...........................................................................................................18

i

Page 3: Ping Pong Bong Final Paper 080319 3

List of Figures and Tables

Figure 1 Initial Project Configuration Sketch......................................................................1Figure 2 Final Project Configuration Sketch.......................................................................2Figure 3 Project Configuration Picture................................................................................2Figure 4 Project Configuration Tube Close-up Picture.......................................................3Figure 5 IR Sensor Front Photo...........................................................................................4Figure 6 IR Sensor Back Photo...........................................................................................4Figure 7 Tube and User IR Sensors.....................................................................................5Figure 8 IR Sensor Specification Response.........................................................................5Figure 9 IR Sensor Responses.............................................................................................6Figure 10 Tube Sensor Differencing...................................................................................7Figure 11 User Sensor Differencing....................................................................................7Figure 12 Fan Photo.............................................................................................................8Figure 13 Motor Block Diagram.........................................................................................9Figure 14 Motor Performance.............................................................................................9Figure 15 Motor Driver Photo...........................................................................................11Figure 16 Software Flow Diagram....................................................................................12Figure 17 Overall Schematic.............................................................................................13Figure 18 Overall Configuration Labeled Picture.............................................................14Figure 19 Ping Pong Bong System Block Diagram..........................................................15Figure 20 Ping Pong Bong Simulation of Step Input........................................................15Figure 21 Simulated Vs. Actual Response Comparison....................................................16

Table 1 Project Equipment List...........................................................................................3Table 2 Microcontroller Data............................................................................................10

ii

Page 4: Ping Pong Bong Final Paper 080319 3

1 SynopsisThis paper describes the details of the Ping Pong Bong project sufficient to build your own. In addition it provides the actual response of the system for both the sensors and actuators. Performance of the system is as follows:

Ping Pong Ball control within one inch maximum deviation within two seconds

Capable of control on an uneven plane/platform

2 Design DescriptionThe goal of the Ping Pong Bong project is to be able to control the position of a ping pong ball in a tube relative to the position determined by a user. An original rendition of the setup can be seen in Figure 1 . Initially one IR sensor was chosen for both inside and outside the tube; rejected due to its non-linear output. A sonar sensor was the next feasible choice because of its very linear range; unfortunately sensor was incoherent. The signal provided by the sensor to by reflected and then sensed diverged too much causing reflections off the tube resulting in a noisy signal. Additionally, the sonar sensor was relatively large in size potentially impacting the flow of air from the fans.

Figure 1 Initial Project Configuration Sketch

The final decision was to use an IR sensor on both ends of the tube, by differencing the signal we were able to obtain an output that was linear enough to provide adequate control of the ping pong position within the tube. To simplify our situation we used another pair of the same IR sensors outside of the tube to determine the desired location of the ball. A sketch of the final setup can be seen in Figure 2.

Page 1 of 22

Page 5: Ping Pong Bong Final Paper 080319 3

Figure 2 Final Project Configuration Sketch

Figure 3 and Figure 4 are pictures of the project configuration. The list of components used to create the Ping Pong Bong can be found in Table 1.

Figure 3 Project Configuration Picture

Page 2 of 22

Page 6: Ping Pong Bong Final Paper 080319 3

Figure 4 Project Configuration Tube Close-up Picture

Table 1 Project Equipment List

Item Quantity DescriptionAnalog to Digital Converter 4

ADC0831 8-bit with serial output

Sensor 4Sharp GP2 Y0A21YKIR Sensor

Actuator 2Link Depot Motor FAN-5015-B

Microcontroller 1ParallaxBS2px

Motor Driver 1 Dual Serial Motor Controller12V Regulator 1 Standard

LCD Display 1Matrix Orbital4x20

Ping Pong Ball 1Standard~ 40mm diameter

Tube 1Florescent Lamp Protector~ 40mm diameter

Page 3 of 22

Page 7: Ping Pong Bong Final Paper 080319 3

2.1 TubeThe tube is a plastic cylinder approximately 30 inches or 76 centimeters in length and 1.57 inches or 4 cm in diameter. With the sensors installed, the range of the Ping Pong Ball within the tube is 29 inches.

2.2 SensorThe Sharp distance sensor is a popular choice for many projects that require accurate distance measurements. This IR sensor is more economical than sonar rangefinders, yet it provides much better performance than other IR alternatives. Interfacing to most microcontrollers is straightforward: the single analog output can be connected to an analog-to-digital converter for taking distance measurements, or the output can be connected to a comparator for threshold detection. The detection range is approximately 10 cm to 80 cm (4" to 32"); the distance-to-output voltage graph is shown below in Figure 8. The sensor uses a 3-pin JST connector; power, ground, and the output signal.

2.2.1 PhotoThe following photos provide the front and rear photos of the IR Sensor, Figure 5 and Figure 6 respectively. Figure 7 provides a vantage point of one tube sensor and one user sensor, refer back to Figure 2 for test setup sensor locations.

Figure 5 IR Sensor Front Photo

Figure 6 IR Sensor Back Photo

Page 4 of 22

Page 8: Ping Pong Bong Final Paper 080319 3

Figure 7 Tube and User IR Sensors

2.2.2 Specification SheetFigure 8 is the IR sensor specification response provided by the manufacturer.

Figure 8 IR Sensor Specification Response

Page 5 of 22

Page 9: Ping Pong Bong Final Paper 080319 3

Feature summary:

4.5 V to 5.5 V operating voltage

30 mA average current consumption 10 cm to 80 cm range (4" to 32") 1.9 V output voltage change over distance range

2.2.3 CalibrationCalibration of the sensor within our setup is not required. The sensors are differenced electronically through software and are discussed further in 2.2.4. This assumes the sensors are identical; if not, there is minimal difference in the sensor that does not sufficiently impact the configuration or the dynamics of the system.

2.2.4 DynamicsFigure 9 provides the actual response of the IR Sensors in the system. There is a noticeable difference between the tube sensors and the user sensors from four to ten inches and has been determined to be because of the tube. Comparison of the user sensors to the IR Sensor specification response shown in Figure 8 confirms the “free space” response of the user sensors matches.

0.00

0.50

1.00

1.50

2.00

2.50

3.00

3.50

0 5 10 15 20 25 30

Distance (Inches)

Ou

tpu

t (V

olt

s)

Sensor 1 Output [inside tube]

Sensor 2 Output[inside tube]

Sensor 3 Output[outside tube]

Sensor 4 Output[outside tube]

Figure 9 IR Sensor Responses

A linear range of sensing was obtained by differencing the pair of IR Sensors. The linear range of the tube sensors and user sensors can be seen in Figure 10 and Figure 11 respectively. The tube sensors provide a linear range of 21 inches with a maximum deviation of 0.76 inches. The user sensors provide a linear range of 20 inches with a maximum deviation of 0.88 inches. The difference in the linear region output can once again be attributed to the tube. Two concepts were used to improve the user sensors. The

Page 6 of 22

Page 10: Ping Pong Bong Final Paper 080319 3

first was inset the user sensors by 1 inch. The second was to use an object to be sensed by the user that was equivalent in size or larger than the ping pong ball, hence the Pillsbury Dough Boy (the sensors detect his head) seen in Figure 4.

y = -0.2323x + 3.5335

-4.00

-3.00

-2.00

-1.00

0.00

1.00

2.00

3.00

4.00

0 5 10 15 20 25 30

Distance (Inches)

Ou

tpu

t (V

olt

s)

Sensor 1 Voltage

Sensor 2 Voltage

Difference

Linear (Difference)

Figure 10 Tube Sensor Differencing

y = -0.2487x + 3.5701

-4.00

-3.00

-2.00

-1.00

0.00

1.00

2.00

3.00

4.00

0 5 10 15 20 25 30

Distance (Inches)

Ou

tpu

t (V

olt

s)

Sensor 1 Output

Sensor 2 Output

Difference

Linear (Difference)

Figure 11 User Sensor Differencing

Page 7 of 22

Page 11: Ping Pong Bong Final Paper 080319 3

2.3 ActuatorThe Ping Pong Bong setup uses two fans of the same make and model for actuators at each end of the tube.

2.3.1 PhotoFigure 12 is a photo of the fan used to actuate the ping pong ball within the tube. There are three wires; ground (black), power (red), and tachometer (yellow).

Figure 12 Fan Photo

2.3.2 Specification Sheet Link Depot Motor FAN-5015-B

o Size:50x50x15mm o Current: 0.16A o Air Flow: 15CFM o Speed: 5200RPM o Power: 1.92W o Bearing: One Ball Bearing o Voltage: 12VDC

2.3.3 CalibrationThe fans were calibrated by providing each with an equivalent PWM or current and observing the ping pong ball movement. Equivalent performance of the fans would be identified by no ball movement; a PWM bias of 8 was necessary to achieve equal output of the fans. Leads to the fans were switched to ensure that the calibration was needed because of the fans and not because of the motor driver, circuitry, or software.

Page 8 of 22

Page 12: Ping Pong Bong Final Paper 080319 3

2.3.4 DynamicsFigure 13 shows a control block diagram representing the dynamics of the fan motor.

The estimated transfer function for the motors is where . was

tested to be 0.2s. Figure 14 shows the simulated response of the motor.

Figure 13 Motor Block Diagram

Figure 14 Motor Performance

Page 9 of 22

Page 13: Ping Pong Bong Final Paper 080319 3

2.4 MicrocontrollerTable 2 provides details for the performance capabilities of the microcontroller used for the project.

Table 2 Microcontroller Data

Product BS2px

Environment0º - 70º C

(32º - 158º F) **Microcontroller Ubicom SX48AC

Processor Speed 32 MHz TurboProgram Execution Speed ~19,000 instructions/sec.

RAM Size38 Bytes

(12 I/O, 26 Variable)Scratch PadRam 128 Bytes

EEPROM (Program) Size8 x 2K Bytes,~4,000 inst.

Number of I/O Pins 16 + 2 Dedicated SerialVoltage Requirements 5 - 12 vdc

Current Draw@ 5 volts55 mA Run,

450 µA SleepSource/Sink Current per I/O 30 mA / 30 mA

Source/SinkCurrent per unit

60 mA / 60 mAper 8 I/O pins

PBASIC Commands* 63PC Interface Serial (19200 baud)

Windows Text EditorVersion

Stampw.exe(v2.2 and up)

* PBASIC Command count totals include PBASIC 2.5 commands on all BS2 models.

Page 10 of 22

Page 14: Ping Pong Bong Final Paper 080319 3

2.5 Motor DriverThe Dual Serial Motor Controller or Motor Driver is a PWB that primarily consists of an H-Bridge and a PIC. As its name implies it utilizes serial communication to receive information from the main microcontroller and drive the motors.

2.5.1 PhotoFigure 15 is a photo of the top profile of the motor driver.

Figure 15 Motor Driver Photo

2.5.2 Specification SheetThe following motor driver details are provided by the manufacturer.

o Speeds: 127 forward, 127 backwards, and brakeo Maximum current: 1A each for two motors

Page 11 of 22

Page 15: Ping Pong Bong Final Paper 080319 3

2.6 Software DesignPID control was chosen to control the position of the ball. Refer to Appendix A Software Code for the Ping Pong Bong control software.

2.6.1 Software FlowchartThe software flowchart is provided in Figure 16. A unique feature of the Ping Pong Bong project was the addition of the “kick out” routines. The tube sensors provide a linear range of ~21 inches in tube that is ~29 inches leaving a “dead zone” of ~3 inches on each side, considering the ping pong ball is ~2 inches in diameter. When the ball enters the “dead zone” it is pushed up against the sensor because positions in the “dead zone” are roughly interpreted as a mirror image about the “dead zone” threshold, which is located at the sensor’s peak voltage, reference Figure 10. In order to correct this misinterpretation the software uses if then statements to identify the special case when both sensors are reading low values. If this instance occurs then the system will provide full force in the opposite direction for 220 ms and clear the PID integral term to prevent integral windup.

Figure 16 Software Flow Diagram

Page 12 of 22

Initialize

Read Sensors

Calculate Desired & Actual Positions

Calculate Drive (PID)

Test Stuck Left

Test Stuck Right

Kick Out of Left

Kick Out of Right

Set Motor Speeds

Page 16: Ping Pong Bong Final Paper 080319 3

2.7 Overall SchematicThe overall schematic seen in Figure 17 includes 4 IR Sensors, 4 Analog to Digital Converters, 2 Fans, one Motor Driver and a Microcontroller which is depicted as input and output pins. Refer to Table 1 for a list of all the components needed to build the Ping Pong Bong.

Figure 17 Overall Schematic

Page 13 of 22

Page 17: Ping Pong Bong Final Paper 080319 3

2.8 Overall Configuration Labeled PhotoFigure 18 is an overall configuration labeled photo; reference Figure 2, Figure 4, and Figure 7 for other perspectives.

Figure 18 Overall Configuration Labeled Picture

Page 14 of 22

User Input

Ball

Power (15V)

Desired Position Sensors

Microcontroller

Junction

Motor Driver

Debug LCD

Page 18: Ping Pong Bong Final Paper 080319 3

3 Control System Design

3.1 Simulation

Figure 19 shows a system block diagram. The simulated system used proportional gain of 6, differential gain of 4, and integral gain of 0. Figure 20 shows the simulated output from a step input.

Figure 19 Ping Pong Bong System Block Diagram

Page 15 of 22

Page 19: Ping Pong Bong Final Paper 080319 3

Figure 20 Ping Pong Bong Simulation of Step Input

Experimental Performance Comparison shows the actual response of the system overlaid with the simulated response. The actual system uses proportional gain of 0.6, differential gain of 25, and integral gain of 0.01. The differences between the simulated and actual gains are mostly accounted for due to differences in scaling between the actual and simulated systems. Additional differences are caused by the methods in determining error, error rate, and error average in the actual system software.

Figure 21 Simulated Vs. Actual Response Comparison

3.2 Results and DiscussionOverall the project was completed successfully with a pleasingly high accuracy and low response time. The system could have been made even more accurate by shortening the distance between the differential sensors, thus improving their linear range. Given the accuracy was within roughly 1 inch, this did not seem necessary. The system’s response time was predominately limited by the amount of differential gain that could be applied, which was limited due to noise in the sensors, causing dramatic error rates. A number of tactics were experimented with and ultimately implemented to significantly reduce the sensor noise, allowing for maximum possible differential gain, which ultimately allowed for maximum proportional gain, minimizing the system’s response time.

3.2.1 Sensor NoiseThe first method of reducing the noise was to use a low-pass filter. This did not help very much because the frequency and amplitude of the noise were both low enough that in order to suppress it, the response of the sensor ended up being reduced, ultimately causing enough additional lag in the system that the filter did more harm than good.

The second approach to reducing the noise in the sensors was to use software implemented averaging filtering. Averaging over a total of 2 readings was sufficient to almost cut in half the amplitude of the noise. The additional phase lag introduced by

Page 16 of 22

Page 20: Ping Pong Bong Final Paper 080319 3

increasing the average count beyond 2 did not outweigh the further reduced sensor noise, and thus an average filter of 2 readings was sustained.

A third addition that helped smooth the sensor output was the introduction of a 10 micro-Farad capacitor to help smooth the regulated 5V supply voltage to the sensors. Evidently the sensors drew current in a sporadic enough manner such that the regulator could not independently hold a very steady 5V. Adding the smoothing capacitor did the trick in stabilizing the supply voltage to the sensors, which in turn granted them more steady voltage outputs.

3.2.2 Integral ControlIt was found helpful to add a very slight touch of integral control to the system to overcome static friction. In many cases, the ball would come to rest from PD control slightly off from the desired position. Adding a very small amount of I control allowed the system to correct for this error. Adding the integral control also enabled the system to function properly even if it were resting on a non-level surface. This was not an original requirement of the system, but rather a bonus capability.

Page 17 of 22

Page 21: Ping Pong Bong Final Paper 080319 3

A.Software Code' {$STAMP BS2px}' {$PBASIC 2.5}

' IO' desired sensor leftDSL_CS PIN 7 ' 0831 chip select active low from BS2DSL_CLK PIN 5 ' Clock pulse from BS2 to 0831DSL_Dout PIN 6 ' Serial data output from 0831 to BS2' desired sensor rightDSR_CS PIN 3 ' 0831 chip select active low from BS2DSR_CLK PIN 1 ' Clock pulse from BS2 to 0831DSR_Dout PIN 2 ' Serial data output from 0831 to BS2' actual sensor rightASR_CS PIN 11 ' 0831 chip select active low from BS2ASR_CLK PIN 9 ' Clock pulse from BS2 to 0831ASR_Dout PIN 10 ' Serial data output from 0831 to BS2' actual sensor leftASL_CS PIN 15 ' 0831 chip select active low from BS2ASL_CLK PIN 13 ' Clock pulse from BS2 to 0831ASL_Dout PIN 14 ' Serial data output from 0831 to BS2MOTOR PIN 8 ' Motor controller serial inputMOTOR_RESET PIN 4 ' Motor controller On/Off line

' CONSTANTSMOTOR_BAUD CON 396 'Set Baud to 9600 (SPECIFIC TO BS2px)' gainsKp CON 60 ' in hundredths (100=gain of 1)Ki CON 1 ' in hundredths (100=gain of 1)Kd CON 250 ' in tenths (10=gain of 1)' biasesMBias CON -8 ' motor bias (since they don't exactly match)DSBias CON -4 ' input sensor biasASBias CON 4 ' actual sensor biasTi CON 5 ' Integral Reset time (how often do we add Err to the Ei term)' average filteringAAveCount CON 2 'size of average for position filtering (smoothing) for actual sensorsDAveCount CON 2 'size of average for position filtering (smoothing) for desired sensors

' VARIABLESDSLData VAR Byte ' left desired sensor dataDSRData VAR Byte ' right desired sensor dataASLData VAR Byte ' left actual sensor data

Page 18 of 22

Page 22: Ping Pong Bong Final Paper 080319 3

ASRData VAR Byte ' right actual sensor dataP VAR Word ' proportional control effort termI VAR Word ' integral control effort termD VAR Word ' differential control effort termDrive VAR Word ' total control effortErr VAR Word ' difference between desired and actual positionsLastErr VAR Word ' store the previous Err term to calculate differentialEi VAR Word ' Err over timeIntCount VAR Byte ' Variable for counting cycles for integral drive (see Ti constant)Sign VAR Word ' variable for calculating signActPos VAR Word ' calculated/filtered actual positionDesPos VAR Word ' calculated/filtered desired position

' INITLastErr = 0 ' clear last errActPos = 0 ' initial actual position = 0DesPos = 0 ' initial desired position = 0Ei = 0 ' clear accumulated errHIGH MOTOR ' set motor serial control line high (for low pulses)HIGH MOTOR_RESET ' motor controller reset (controller on)

' PROGRAMMain: GOSUB ReadDSL GOSUB ReadDSR GOSUB ReadASL GOSUB ReadASR GOSUB TestForStuck GOSUB CalcPosition GOSUB CalcDrive GOSUB RunMotorsGOTO main

' subroutinesReadDSL: ' Acquire conversion from 0831 LOW DSL_CS ' Select the chip LOW DSL_CLK ' Ready the clock line. PULSOUT DSL_CLK,10 ' Send a 10 uS clock pulse to the 0831 SHIFTIN DSL_Dout, DSL_CLK, MSBPOST,[DSLData\8] ' Shift in data HIGH DSL_CS ' Stop conversionRETURN

ReadDSR: ' Acquire conversion from 0831 LOW DSR_CS ' Select the chip LOW DSR_CLK ' Ready the clock line.

Page 19 of 22

Page 23: Ping Pong Bong Final Paper 080319 3

PULSOUT DSR_CLK,10 ' Send a 10 uS clock pulse to the 0831 SHIFTIN DSR_Dout, DSR_CLK, MSBPOST,[DSRData\8] ' Shift in data HIGH DSR_CS ' Stop conversionRETURN

ReadASL: ' Acquire conversion from 0831 LOW ASL_CS ' Select the chip LOW ASL_CLK ' Ready the clock line. PULSOUT ASL_CLK,10 ' Send a 10 uS clock pulse to the 0831 SHIFTIN ASL_Dout, ASL_CLK, MSBPOST,[ASLData\8] ' Shift in data HIGH ASL_CS ' Stop conversionRETURN

ReadASR: ' Acquire conversion from 0831 LOW ASR_CS ' Select the chip LOW ASR_CLK ' Ready the clock line. PULSOUT ASR_CLK,10 ' Send a 10 uS clock pulse to the 0831 SHIFTIN ASR_Dout, ASR_CLK, MSBPOST,[ASRData\8] ' Shift in data HIGH ASR_CS ' Stop conversionRETURN

CalcPosition: ' calculate the actual and desired positions using sensor biasing, and filtering ' the actual position is the right actual sensor differenced with the left actual sensor ActPos = ActPos * (AAveCount - 1) + (ASRData - ASLData + ASBias) Sign = ActPos GOSUB SetSign ActPos = ABS ActPos / AAveCount ActPos = ActPos * Sign ' the desired position is the right desired sensor differenced with the left desired sensor DesPos = DesPos * (DAveCount - 1) + (DSRData - DSLData + DSBias) Sign = DesPos GOSUB SetSign DesPos = ABS DesPos DesPos = DesPos / DAveCount ' if we're within roughly the inside 16 inches, IF ( DesPos < 70 ) THEN DesPos = DesPos * 11 / 10 ' scale the desired position due to its slight lack of linearity ENDIF DesPos = DesPos * SignRETURN

TestForStuck: ' look for threshold crossings that would indicate the ball is stuck at one end of the tube ' if the right sensor reads 'very far away', and the left sensor doesn't read 'pretty close', IF ( ASRData < 18 AND ASLData < 80 ) THEN

Page 20 of 22

Page 24: Ping Pong Bong Final Paper 080319 3

GOTO StuckLeft ' assume we're stuck against the left sensor/fan ' if the left sensor reads 'very far away', and the right sensor doesn't read 'pretty close', ELSEIF ( ASLData < 21 AND ASRData < 80 ) THEN GOTO StuckRight ' assume we're stuck against the right sensor/fan ENDIFRETURN

StuckLeft: ' routine to kick the ball away from the left end of the tube SEROUT MOTOR, MOTOR_BAUD, [128, 0, 0, 0] ' turn off the right motor SEROUT MOTOR, MOTOR_BAUD, [128, 0, 2, 127] ' turn on the left motor full blast PAUSE 220 ' wait a little while to kick the ball out Ei = 0 ' clear the integral memory in case we've been stuck here for very longGOTO Main

StuckRight: ' routine to kick the ball away from the right end of the tube SEROUT MOTOR, MOTOR_BAUD, [128, 0, 0, 127] ' turn on the right motor full blast SEROUT MOTOR, MOTOR_BAUD, [128, 0, 2, 0] ' turn off the left motor PAUSE 220 ' wait a little while to kick the ball out Ei = 0 ' clear the integral memory in case we've been stuck here for very longGOTO Main

RunMotors: ' send control speed signal to motor drivers SEROUT MOTOR, MOTOR_BAUD, [128, 0, 0, (127 - Drive)/2] ' run right motor at 50% speed - drive value SEROUT MOTOR, MOTOR_BAUD, [128, 0, 2, (127 + Drive)/2] ' run left motor at 50% speed + drive valueRETURN

CalcDrive: ' calculate the total control effort GOSUB ErrorCalc ' calculate error GOSUB PropCalc ' Perform proportional error calcs GOSUB IntCalc ' Perform intigral calcs GOSUB DerivCalc ' Perform derivitive calcs Drive = (MBias + P + I + D) ' calculate total drive Sign = Drive ' Sign adjust to max of 127 min -127 GOSUB SetSign Drive = ABS Drive MAX 127 ' Limit drive to motor capability Drive = Drive * Sign ' restore signRETURN

'********** Calculate Error - Sign adjustedErrorCalc: LastErr = Err ' save last error for derivitive calc Err = (DesPos - ActPos) ' Calculate position errorRETURN

Page 21 of 22

Page 25: Ping Pong Bong Final Paper 080319 3

'*********** Proportional Drive - Sign adjustedPropCalc: Sign = Err GOSUB SetSign P = ABS Err * Kp / 100 ' Apply Kp gain in hundredths P = P * SignRETURN

'*********** INTIGRAL DRIVE - Sign adjustedIntCalc: IntCount = IntCount + 1 'Add to counter for reset time IF IntCount < Ti THEN IntDone ' Not at reset count? -- done Ei = Ei + Err ' Accumulate err Sign = Ei GOSUB SetSign Ei = ABS Ei MAX 6000 ' limit to prevent windup (the only potential for windup is if the ball gets stuck at an end and doesn't get kicked out) I = Ei * Ki / 100 ' Apply integral gain in hundredths Ei = Ei * Sign I = I * Sign IntCount = 0 ' reset counter IntDone:RETURN

'*********** DERIVATIVE DRIVE - Sign adjustedDerivCalc: ' Calculate amount of derivative drive based on the difference of last error D = Err - LastErr Sign = D GOSUB SetSign D = ABS D * Kd / 10 ' apply the derivitive gain in tenths D = D * SignRETURN

'********** Set sign of valueSetSign: IF Sign.BIT15 = 0 THEN SignPos ' If signbit is 1, then negative Sign = -1 RETURN SignPos: Sign = 1 SignDone:RETURN

Page 22 of 22


Recommended