Beirut Master 4000 Progress Report ECSE-4460 Control System Design

Size: px
Start display at page:

Download "Beirut Master 4000 Progress Report ECSE-4460 Control System Design"

Transcription

1 Beirut Master 4000 Progress Report ECSE-4460 Control System Design Team 2 Larry Cole Vinay Shah Danish Zia Bert Hallonquist Wednesday, March 30, 2005 Rensselaer Polytechnic Institute

2 Abstract This document describes the progress of a design project which will attempt to successfully launch a ball into a cup. By mounting a pneumatic launcher on a pan and tilt mechanism a ping pong ball can be launched to within a range of locations. An iterative learning algorithm has been developed to generate solutions for pan and tilt angles which successfully place the ball in the cup. A controller is being designed through the use of experimentation, modeling, and simulation to quickly command the motor to the desired location. An automated feedback system will be developed using a camera coupled with image processing. The overall goal of this project is to design an automated system to quickly place a ball in a cup my minimizing the time it takes to position the launcher and the number of iterations required to converge to the solution. There have been some delay in the design process, but with increased enthusiasm and willingness to put in more hours than initially planned, we are still confident that we will meet our objective. ii

3 Contents Table of Contents Abstract... ii Introduction... 2 Preliminary Results... 3 Motor Control... 3 Launcher System... 8 Feedback System Learning Algorithm Summary of Progress Bibliography Appix Statement of Contribution Table of Figures Figure 1 Simulink model of single decoupled axis... 3 Figure 2 Pan axis velocity curves... 4 Figure 3 Tilt axis velocity curves... 4 Figure 4 Pan axis velocity versus torque... 5 Figure 5 Tilt axis velocity versus torque... 5 Figure 6 Tilt axis root locus... 7 Figure 8 Step response of PID controlled tilt axis... 8 Figure 9 Gain and Phase margin measure for tilt axis... 8 Figure 10 Valve Dimensions... 9 Figure 11 Ping Pong ball gun Figure 12 Launching System setup Figure 13 Launcher Mount Figure 14 Mounted Launcher Figure 15 Non-inverting Amplifier circuit Figure 16 Diagram of pixel transformation Figure 17 Newton-Raphson method (r,z) plane Figure 18 Newton-Raphson method (φ,r) plane Figure 19 Schroder method (r,z) plane Figure 20 Schroder method (φ, r) plane Figure 21 Overall System model Figure 22 Schedule

4 Introduction For this project we will launch a projectile toward a target. We will mount a launcher on the pan-and-tilt device, so that the launch angle is determined by the pan-and-tilt. After the ball is fired a camera will capture the point where the ball hits the ground. The time at which the ball strikes the ground will be determined by piezo devices placed around the area of the target. The camera will capture a single frame image of the ball and the target at this time. The image will be processed and sent to the learning algorithm which will determine the angles for the next shot. This iterative learning system will be able to hit the target within eight attempts. Our motivation was to create a machine that can automatically master the game of Beirut, a popular game among college students where players must throw ping pong balls into cups. However, the concept of the iterative learning algorithm has several applications outside of the scope of our project. This implementation can be used for military applications. Using satellite imaging, the algorithm can be used to iteratively learn how to hit targets with missiles. The robotics industry is interested in using iterative learning algorithms to develop smarter robots for various applications. The motors will be controlled by a PID controller to move the launcher into a desired position. The controllers will minimize the settling time of the response, have zero steady state error, minimum over shoot, and should be able to track a desired trajectory. Currently we have fallen behind in our planned progress, however adequate progress has been made. The launching system is connected to the air tank and is ready to be tested. It is not yet mounted on the pan-and-tilt, but the method for doing so is planned out and will be implemented soon. Modification of the launcher nozzle is a future task to be looked at. For the controller, a MATLAB script has been written and tested to identify model parameters. An initial design approach for the controllers have been established and tested with an estimated model. For the feedback system, integration of the piezo devices and camera has yet to be completed, however a MATLAB script to detect the ball and target has been completed. The learning algorithm is completed and will only require minor tweaks when implemented on the actual system. It uses the Schröder method because it converged to the solution faster than the other possible methods. Future tasks include calibrating the learning algorithm to be compatible with the feedback system and launching system. Friction identification turned out to be an unanticipated challenge in that it was more time consuming than initially planned. Another challenge was to rethink the launcher system so that pressure doesn t build up indefinitely in the tubes. This would cause tubing to fly off of the barbs that they were attached to. In our original plans we hadn t for-seen that this would occur. Preliminary Results 2

5 Motor Control The plant is being modeled as a system with two decoupled axis. Coupling between the two axis may occur due to Coriolis affects, however at this point we assume it to be a negligible affect and model it as noise to the system. If this assumption is proven to be invalid during model validation stages, Coriolis affects will be investigated and implemented in the model. The model of a single axis is shown in Figure 1. Sign Bceff Coulomb f riction 1/Jeff 1 s Integrator 1 s Bveff sin m*g*l v iscous f riction grav ity loading position data input N*Kt*Ki From Workspace voltage Figure 1 Simulink model of single decoupled axis The system transforms an input voltage to a position of the axis (in radians) while considering affects due to friction and gravity loading. Non-linearities such as Coulomb friction, quantization, and saturation exist when attempting to realistically model the system. By ignoring quantization and saturation affects, a differential equation of the system can be written as: J θ = Nτ + mglsin θ B θ B Sign( θ ) (1) eff m v c Where J eff is the effective load inertia, N is the gear ratio, τ m is the motor torque, m is the mass, g is gravity, l is the center of gravity of the load, B is the viscous friction, and is the Coulomb fiction. The motor torque can be calculated as follow: τ = VNK K (2) m t i v B c Where V is the input voltage, N is the gear ratio once again, K t is the torque constant (.0436 N*m/A in our case) and K i is the amplifier gain (0.1 Amp/volt). Thus the parameters which need to be identified are the viscous and Coulomb friction, the effective inertia, and the gravity loading term mgl. Multiple methods of obtaining this data are being explored in order to find the most accurate representation of the system. [5] 3

6 Friction Identification Friction parameters have been identified by analyzing the relationship between steady state velocities due to constant torque inputs to the system. First a MATLAB script (Appix A.1 ) was written to acquire all the necessary data. Data was gathered for a set of voltages within the saturation bounds of the motor. Each voltage experiment was run five times and then averaged in an attempt to cancel out any zero mean noise to the system. A 10 volt 1.5 second pulse was initially inputted to the system in order to overcome the stiction of the system. The velocity of the system was calculated by a finite difference on the output position of the system. This velocity was then filtered using a 12 th order Butterworth filter with a cut of frequency of.065f s which is equal to a cut off of 65 Hz. The resulting torque due to a given input voltage was calculated according to equation 2. The velocities versus time of the pan and tilt motor are shown in Figure 2 and Figure 3 respectively. The value used for the steady state velocity was simply the last value in the time history of each of the velocity curves. Using these values, curves of steady state velocity versus torque were generated. A linear regression was preformed for both operating regions of each motor. The viscous friction for both the positive and negative region for each axis is determined by noting the slope of each of the line segments. The Coulomb friction is the value at which these line segments intersect the torque axis. Table 1 summarizes the friction parameters for the system. 25 Friction Identification: Pan Motor 25 Friction Identification: Tiltmotor Velocity (rads/sec) Velocity (rads/sec) time (ms) x 10 4 Figure 2 Pan axis velocity curves time (ms) Figure 3 Tilt axis velocity curves 4

7 0.1 Friction Indentification: Pan Motor 0.15 Friction Indentification: Tilt Motor torque (N*m) torque (N*m) velocity (rads/sec) Figure 4 Pan axis velocity versus torque velocity (rads/sec) Figure 5 Tilt axis velocity versus torque Pan Motor Viscous (N. m. s/rad) Coulomb (N. m) Positive Negative Tilt Motor Viscous (N. m. s/rad) Coulomb (N. m) Positive Negative Table 1 Summary of friction parameters Inertia Estimates and Gravity Loading Two of the required parameters to create the system model are the load inertia (J L ) as well as the gravity loading. Due to the complexity of the model, both these parameters were calculated using the SolidWorks 2004 software. First, the launcher and mount for our system was created inside SolidWorks 2004, and attached to the existed pan-tilt mechanism model designed by Ben Potsaid. Next, the density of each part of the model was assigned. Then a coordinate system relative to each of the two motors was defined, and aligned with the rotation axis. All the parts causing an inertial load on the each motor were selected and their Mass Properties relative to the coordinate system defined for that motor was displayed. This revealed the 3x3 inertia matrix, as well as the total mass and center of mass of these parts. From these, the load inertia and gravity loading were calculated. Parameter Identification Another method uses a least squares estimation method to determine all the parameters in a single experiment. However, the results of this method are depant on the type of input given. The input must sufficiently exciting which means the effects of the different parameters can be observed. Thus, a good input for one system may be a poor input for another. By lumping the parameters in equation 2 the dynamic model of a single axis can rewritten as: 5

8 θ = a θ a Sign( θ) + a V + a sinθ (3) By comparing equation 3 with equation 2 it is easy to observe that a = B /J (4) 1 v eff a = B /J (5) 2 c eff a = K K N/J (6) 3 t i eff a = mgl/j (7) 4 eff Thus, by setting values of J eff, B v, B c, K t, K i, N, m, g, and l in the Simulink model in figure 1 essentially values of a 1, a 2, a 3, and a 4 are being set. The least squares estimation algorithm was developed (Appix A.4) and tested on the above model for various cases of the parameters above. We were able to successfully achieve reasonably accurate results under a no-load test case, however the accuracy greatly diminished when attempting to model a non no-load case. Table 2 compares the actual versus experimentally determined values of the parameters for the no load case. The input was a chirp signal from.1 to.5 Hz for a duration of 30 seconds. a 1 a 2 a 3 a 4 Actual Experimentally Determined Table 2 Comparison of actual and experimentally determined parameters Currently we are experimenting with different input cases for a non no-load situation. Although these input cases will probably still may not be sufficiently exciting for our physical system, it will help us determine how changes in our input signal affect our ability to identify the various parameters. One can verify that the system was excited with a sufficiently exciting input by observing a small value for the condition of the A T A matrix with large Eigen values. [3] Controller Design Initially we planned on exploring three types of controllers, the classical PID controller, a finite settling time (also known as a ripple free) controller, and a full state feedback controller. Finite settling time controllers typically require very large gains or very slow sample times which is not acceptable for our design. A full state feedback controller typically requires accurate estimations of the states of the system. However, velocity estimations have limited accuracy and therefore the full state feedback would have limited control. There are approaches to overcome such problems, however due to limited time and the confidence that a PID control will work sufficiently well these approaches will not be investigated. 6

9 In order to do control design first we must have a linear representation of the plant. Since the model of the system is not fully complete, the control design approach below will only be demonstrated for one axis. The second axis will undergo a similar design approach. Approximate values for the system parameters were used and the model was linearized resulting in the following transfer function: (8) s^ s By doing a root locus analysis a starting value for the proportional gain was picked. 8 Root Locus 6 Imaginary Axis System: test Gain: 2.79 Pole: i Damping: 1 Overshoot (%): 0 Frequency (rad/sec): 7.69 Step PID PID Controller Zero-Order Hold In1Out1 non linear motor si mout To Workspace Real Axis Figure 6 Tilt axis root locus Figure 7 Tilt axis root locus Figure 6 shows that a gain of 2.79 would yield a critically damped response, however when tested with the non-linear model, as shown in Figure 7, the response was overdamped. Thus an integral term was used to reduce the rise time and a derivative term to reduce the resulting overshoot. The set of PID gains which resulted in the step response shown is figure 8 are k p = 22, k i = 2.0, and k d = 1.6. Since our controller is going to be digitally implemented, the PID controller is then discretized using a Tustin continous to discrete operation. The resulting controller is in the form: 3222 z^ z (9) z^2-1 The step response is shown in Figure 8. 7

10 1.4 tilt axis step response position (rad) time (s) Figure 8 Step response of PID controlled tilt axis Another important aspect to consider when designing a controller is its overall robustness. Because the controller is designed around a linearized model, there may be operating regions that are unstable. If the controller is adequately robust then the unstable operating points should not be a problem. The systems overall robustness is measured with two parameters, gain and phase margins which are shown below. [1] 200 Bode Diagram Gm = Inf db (at Inf rad/sec), Pm = 38.6 deg (at 19.1 rad/sec) 150 Magnitude (db) Phase (deg) Frequency (rad/sec) Figure 9 Gain and Phase margin measure for tilt axis The current model of the tilt axis has an infinite gain margin and a phase margin of 38.6 degrees. These are acceptable values to ensure that our system does not become unstable at its operating points. Launcher System In the design strategy section of the project proposal report we had proposed the following method of creating a launcher: The launcher will make use of the compressed air in the laboratory. From the compressed air tank we will run a tube to an electronically controlled on-off valve. The valve will be off to start. When the valve receives the voltage signal (via wires) sent from the controller, it will open and the air will be allowed to flow. The air will then flow into a tube where a ping pong ball rests. The tube will 8

11 properly fit around the ball so that the air will push the ball outwards. At the of the tube there will be a choking device so that the ball will be stuck and will only be fired from the tube if the air pressure inside the tube reaches a certain level. In this way the initial velocity of the projectile will be the same every time. Multiple balls will be able to be in the tube at one time, so that the device need not be reloaded every time. The launcher was contrasted based on this design strategy. The first thing we did was to order a ping pong ball gun and a valve to fit our needs. The valve that we ordered was a proportional valve, so that we could completely control the airflow by applying the proper voltage to it. The valve has wire connectors, a control voltage of 0 to 5 volts, an orifice of inches, and a rated pressure of 100psi. [7] In addition, the valve has the following specifications (measured in inches): Figure 10 Valve Dimensions It was at this point that the first construction challenge arose. The inlet and outlet ports for the valve are threaded holes, as shown in the figure above. It was now on us to find a way to connect the inlet port of the valve to the large air tank nozzle in the lab. This problem was solved in the following fashion. We were able to find a barb to screw into the valve, which could then in turn have tubing attached to its other side. However, of the barbs that could screw into this size threading (10-32), none supported a tube size that would be large enough to fit onto the air tank nozzle in the lab. The barb chosen supports tubing with an inner diameter of 1/8 of an inch, and the tubing in the lab which fits over the nozzle has an inner diameter of 3/8 of an inch. To solve this we bought a device made for stepping down from high diameter tubing to low diameter. It is a simple device with ribs of the proper sizes so that each tube can connect to one of the device s sides, allowing flow from one tube to another. After this we had to connect the other side of the valve to the launcher body. The launcher body was constructed from the parts of a ping pong ball gun which we purchased online, which is shown in the figure below. 9

12 Figure 11 Ping Pong ball gun [4] The front handle was removed, as well as the back of the gun, which includes the other handle and a secondary tube which allows the user to manually pump air into the tube which holds the balls. Only the single tube with the balls in it and the squeezing nozzle were required for our purposes. We now had to connect the back of this launcher to tubing with an inner diameter of 1/8 of an inch. The back of the launcher consisted of a small hole set in plastic material. Using a steel tap of thread size, we enlarged this hole and threaded it. We could then place the same barb into the back of this launcher as the one that screws into the valve, and have one tube used to connect the two. With this setup in place it was possible to run an initial test to see if it worked correctly. A problem immediately arose from this test. When the valve was open the air would flow freely through it, but when it was closed the pressure would keep building inside the tubing until finally a tube would fire off of the barb that held it. We had to rethink our strategy at this point and come up with a plan that didn t involve indefinite pressure build up. The plan that we adopted is as follows: Instead of connecting the air tank to the valve directly and then to the launcher, we now connect the air tank to a split in the tubing. One side of this split will go to the inlet of the valve and the outlet of the valve will be left open to the room. The other side of the split will go to the back of the launcher. In this fashion we can have the air tank continually supplying air without any pressure build up. When the valve is open the air will be able to flow freely out into the room without any considerable pressure build up in the launcher. When the valve becomes closed then the air will flow to the launcher and fire a ball. Implementing this plan was not tough because the lab already has a 3-way split device among the tubing that is there. This means that we will be making the transition from the larger tubing to smaller tubing twice now, because the launcher and the valve only support 1/8 in. diameter tubing while the split device only supports 3/8 in. diameter tubing. The following figure illustrates the current setup of the launching system: 10

13 Figure 12 Launching System setup Mounting the launcher to the tilt shaft presents several logistical issues. The mount must be strong enough to hold the launcher in place without deforming the tube. Since the launcher will be moving, it must be able to keep the tube straight. The mount will consist of a mounting plate and a U-bolt to connect the launcher to the mounting plate. The mounting plate will be connected to the motor shaft by a clamp. The clamp will consist of two ming plates med around the shaft and screwed into the mounting plate. The U-bolt will be connected to the mounting plate. The diameter of the arc of the U-bolt is a little bit larger than the diameter of the launcher. This allows for the launcher to fit snuggly in place. A main concern is sliding of the launcher that may occur when the motor is turning. There are a few potential actions to solve this problem. The first solution that would be attempted is to apply a rubber ring around the area of the launcher being clamped to the motor. This will increase the diameter of the launcher, thus allowing for a tighter fit. The rubber is compressible, so the U-bolt will deform the rubber before deforming the launcher. The second solution is to use melding glue to attach the launcher to the U-bolt, or the ming plates to the tilt shaft if necessary. Obviously gluing to the tilt shaft is less than ideal because it would become a permanent fixture to the shaft. The following two SolidWorks models show how the launcher will be mounted. 11

14 Figure 13 Launcher Mount Figure 14 Mounted Launcher Feedback System Camera/Piezo integration Currently the feedback system has been put on hold so that the focus can be made on the ball launching and launcher mounting. However the plan for implementation has been further developed. The piezo devices will be attached to an aluminum sheet. When the ball hits the aluminum the impact will be strong enough to induce a small voltage. One member of the team has had experience with using piezo devices for this type of application and knows that they are sensitive enough to pick up the impact of the ball. The small voltage will be amplified through a non-inverting amplifier. Figure 15 Non-inverting Amplifier circuit The voltage signal will be amplified using the circuit in Figure 15. The parameters R f, R z, and R in will be determined when the voltage range for the impact is found. They will be found by manipulating the equation 10. The ideal value for V out is 5V, so the values of R f and R in should be set to obtain that value. V R + R V R out f in = (10) in in 12

15 Note that the amplifier does not dep on R z, but it s value will be set to the parallel combination of R f and R in. This is to reduce the affect of small variations cause by the input current. The amplified signal will be sent back to XPC target. There will be a block that constantly checks the input. When this is set high by the amplifier a variable will be changed which will trigger a script on the laptop that the ball has hit. Then a frame set back from the time the signal is reach will be pulled and be processed. The exact delay of the frame will be determined experimentally by manually looking at frames during the first few firings of the launcher. Image Processing The basic premise of the image processing aspect of the feedback is to compare the received image of the ball hitting the piezo devices with an image taken prior to launching. Before the ball is launched a snapshot is taken of the target area. Using binarization techniques, the center of the target and size of the target is found. After the image of the ball landing is found, a ball finding algorithm is performed. This will convert the color image of the ball to a binary image similar to that of the binary image of the target taken earlier. The level of noise in the binary image of the ball is much greater than that of the target. Morphological operations are performed on the binary image of the ball to eliminate the noise. The same algorithm to find the center of the target will be applied to find the center of the ball. This coordinate will be compared to the area of the target previously found. If the coordinate is within the target area then the launch is successful and no further action is necessary. If the ball is outside the target, pixel transformations are performed to find the location of the ball relative to the target in polar coordinates. Pixel transformations The first step in converting the image plane to the polar coordinates with respect to the launcher is to determine the size of each pixel. To do this the angle of the camera s field of view must be determined. This was done by measuring the number of pixels that cover a 5 inch piece of tape both vertically and horizontally. Using that information the angle of the field of view can be determined by equation 11. 5N Θ = sin 1 ( ) (11) 2 ph Where Θ is the angle of the field of view, p is the number of pixels in the row/column containing the tape, h is the height of the camera, and N is the total number of pixels in the row. 13

16 The two angles found are of the horizontal angle, and for the vertical angle. Using these values the distance of pixel in the image plane can be found by equation 12. 2hpsin Θx.y D( p) = (12) N Where D is the distance relative to pixel (1,1), h is the height of the camera, p is the pixel location, N is the total number of pixels in the row/column, and Θ is the angle of the camera s field of view. Using the information found by equation 12, the polar coordinates can be calculated. Let M be the total number of columns, N be the total number of rows, and d be the distance from the launcher to pixel (1,N/2), and Φ=0 correspond to the line that connects the launcher to pixel (M/2,N/2). The value of d for a camera at height h, and distance from launcher D L can be found by equation 13. d = DL hsin(θ) (13) r M (x 0, y 0 ) Launcher Φ d N Image Plane Figure 16 Diagram of pixel transformation Using basic trigonometry the equations for r and Φ can be found. r 2 2 = ( d + D( x0 )) + ( D( y0) D( N / 2)) (14) 1 D( y0) D( N Φ = sin ( r / 2) ) (15) Learning Algorithm 14

17 The learning algorithm will use an iterative control algorithm to obtain a new pan and tilt theta input based on the position error and the previous input. Initially the learning algorithm was developed using the Newton-Raphson root-finding method. Since the coordinate system being used is cylindrical, the radial distance (r) from the launcher is only affected by the tilt angle (Θ 1 ). Similarly, the horizontal angle (φ) between the launcher-ball and launcher-center zero lines is only affected by the pan angle (Θ 2 ). Using the general Newton-Raphson formulas, equations 16 and 17 are formed in order to determine new angles based on the previous try. The Newton-Raphson method derives a new estimate for Θ based on the previous estimate and the ratio of the error to the derivative evaluated at the previous estimate. Θ = Θ + 1( k+ 1) 1( k) Θ = Θ + 2( k+ 1) 2( k) ( r r ) desired dr dθ 1( k ) ( φ φ ) desired dϕ dθ k 2( k ) k (16) (17) In order to use these equations, the derivate of r with respect to Θ 1 and φ with respect to Θ 2 are found. The radial distance r as a function of the tilt angle is a simple physics equation relating to projectile motion as seen in equation 18. Here, V 0 is the initial launch velocity, g is the gravitational acceleration, and h is the height of the launcher above the target area. The horizontal angle φ is the same value as the pan angle, as seen in equation ( ) V0sin Θ 1 + V0 sin Θ 1 + 2gh V0 cosθ1 r = (18) g ϕ =Θ (19) 2 The derivatives of these two equations are taken in order to find the behavior of r and φ with respect to their angles. The derivatives are taken in Maple and confirmed in MATLAB as well as hand calculations. Equations 20 and 21 represent these derivatives. dr dθ 1 2 V0 sin( Θ1)cos( Θ1) V0 cos( Θ 1) + V0 cos( Θ1) 2 2 V0 sin( Θ 1) + 2gh = g dφ = 1 dθ ( gh ) V sin( Θ ) + V sin( Θ ) + 2 V sin( Θ ) g (20) (21) 15

18 These derivatives are then substituted back into equations 16 and 17 in order to complete the algorithm. The derivative of φ with respect to Θ 2 being a value of 1 leads to the correction in the pan angle to be based linearly on the error. In order to improve upon this algorithm further, the root-finding algorithm is changed from the Newton-Raphson method to the Schröder method. Instead of just relying on the single derivative, the Schröder also deps on the double derivative of the error with respect to the angle. Since the double derivative of φ as a function of the pan angle is zero, this new method simplifies to the Newton-Raphson method for the pan angle. However the formula to estimate the new value of the tilt angle is changed as seen in equation 22. Θ = Θ + ( r r ) desired dr k d Θ1( k ) 1( k+ 1) 1( k) 2 2 dr d r + ( rdesired r k ) 2 dθ 1( k ) dθ 1( k ) (22) The expression for the derivative that was obtained for the Newton-Raphson method can be used here as well. In addition, it is used to find the double derivative which comes out to a rather complicated formula seen in equation 23. This formula is then substituted in equation 22 to complete the root-finding algorithm. [6] 2 dr dθ 2 1 VcosΘsin Θ VcosΘ VsinΘ VsinΘ + Θ = g Vcos 2 2 3/2 0 1 (V sin Θ+ 1 2 gh) V0sin Θ+ 1 2gh V0sin Θ+ 1 2gh VsinΘcosΘ 2Vcos Θ + Θ ( Θ + Θ + gh) Θ g g Vsin Vsin 0 Θ+ 1 2gh V0sin 1 V0 sin 1 2 V0cos 1 (23) In order to test the two different algorithms, a physics model was created to simulate the motion of the ping pong ball as affected by disturbance (air friction, spin). The model was based on basic projectile physics with the addition of three coefficients, two of which simulate air friction and the third adds a spin disturbance. Two coefficients (K z and K r ) attenuate the velocity of the r and z axis as shown in equations 24 and 25. The third coefficient (K φ ) creates a spin by attenuating the φ coordinate as shown in equation (26). The model can be seen in Appix A.8 and the two M-files used to simulate each algorithm can be found in Appix A.9 and A.10. [2] Vz( k+ 1) = V0sin Θ1 KzVz( k) (24) 16

19 Vr( k+ 1) = V0 cos Θ1 KrVr( k) (25) ϕ k 1 ϕ + 0 Vr( k ) K ϕ (26) Both algorithms were tested for a variety of desired coordinates and coefficients. After conducting several tests, it was determined that the algorithm using the Schröder s rootfinding method is more efficient at correcting for the radial distance from the launcher. One of the tests that demonstrate this improvement well is shown in Figures 17 through 20. When the radial distance of the target is set to 2 meters, and the φ angle is set to 45 degrees, it takes the Newton-Raphson method four tries to hit the target. When the Schröder method is used, the target is hit in 3 tries, but the radial distance is actually matched in only 2 tries. In most tests conducted, the algorithm using Schröder s method beat the algorithm using the Newton-Raphson method by at least one try. More of these tests can be seen in Appix A.11. Figure 17 Newton-Raphson method (r,z) plane Figure 18 Newton-Raphson method (φ,r) plane Figure 19 Schroder method (r,z) plane Figure 20 Schroder method (φ, r) plane 17

20 Thus the Schröder method was chosen to be implemented when the algorithm is integrated with the rest of the machine. The number of attempts to hit the target never exceeded four using either of the two algorithms. Assuming correct functionality of the rest of the mechanism, these tests ensure that the learning algorithm should be able to hit the target within the eight attempts specified in the project proposal. Summary of Progress Modeling of the system has come a long ways since the project proposal. Many of the subcomponents of the overall model have been developed and implemented in the model of the system. Figure 21 Overall System model Currently the ball trajectory model and the learning algorithm are completed. The framework for the motor model is completed, however parameter identification can not occur until after the system has been built. Kinematics of the system are also depant on the completion of building the system. The sensor model currently assumes perfect sensing, however a more realistic model is being developed. This model will take into 18

21 account the limited visibility of the webcam, possible processing delays, and sensor noise. At this point we were scheduled to have completed parameter identification, model verification, and start of controller design. Due to the fact that our system is still not completely built, these parameters do not yet exist and thus parameter identification can not take place. Since there is no physical system in place to compare the model to, model verification is also not possible. However, these setbacks have not halted productivity. An algorithm was developed and tested on a model to identify the parameters of the model. This algorithm is also self verifying because based on the resulting Eigen values the accuracy of these parameters can be determined. Initial control design has also taken place. Using estimated values for inertia and other parameters a controller was designed to generate a response for the tilt motor with almost no overshoot, a rise time of less than one second, and fast settling time. According to the schedule that we created for the project proposal, the launching system had three main tasks scheduled to be done before the current date. These are accuracy testing of the gun, gun modification as needed and further testing, and the mounting of the gun onto the pan-tilt device. Because of the difficulties we had with pressure build up, we had to rethink our plan before it was possible to test the system for accuracy. We did some extensive modifications to the gun in order to get it working, as described in the preliminary results section. Therefore we consider this task to have been fulfilled, although there may be some future modification necessary. Because of this delay our accuracy testing is way behind schedule. We have not yet taken any analytical measurements as to the accuracy of the gun given the current setup. This is something which will be done as soon as possible. The third task that needed to be completed was the mounting of the gun onto the pan-tilt device. This is also slightly behind schedule, although we have fully developed a plan for this task and have purchased the parts necessary for this plan. All that is left to do is to implement the plan, so this task is not too far behind schedule. The details of the gun mounting are described in an earlier section of this report. The challenges to the construction of the launcher are described in the preliminary results section. I will summarize them here. First, an electronically controlled valve and launcher body needed to be acquired. This was done by ordering the valve and a ping pong ball gun online, and making modifications to the ping pong ball gun. Next was the issue of attaching the valve to the air tank in the lab. A barb was purchased to screw into the inlet of the valve. Tubing was purchased to attach to this barb and run to the air tank in the lab. Because the barb only supports 1/8 in. diameter tubing and the air tank needs 3/8 in. diameter tubing, a device was purchased to step up from the smaller tuning size to the larger. The larger tubing did not need to be bought because there was some free for use in the lab. After this it was necessary to attach the valve to the gun. A tap was used to bore a threaded hole into the back of the launcher, and the same size barb that the valve uses 19

22 was placed into this launcher. It was then possible to use one tube to connect the two. The last challenge was to remove the pressure build up which was causing tubing to come loose. This was done by reworking our design so that the airflow splits, and the valve controls whether the air goes to the launcher or flows freely into the room (instead of just building up in the tubing as with our previous design). For the remainder of the project we have the following tasks for the launching system. First comes the mounting of the gun onto the pan-tilt. Second we will test for accuracy and to get an uncertainty measurement of the launched balls. Our launcher fires balls a little too fast for our convenience, so if possible we will then develop a plan to modify the nozzle of the gun or to modify the balls used. This will bring the initial velocity down to a more desirable value. If this is done we will retest for accuracy. Another challenge is integrating the launcher with the controller, i.e, how exactly do we wire the electronic valve to our system so that it can be controlled by our code. This is a very important step and so it will also be one of the first things taken care of. After this the launching system will be complete, unless any further problems arise. Progress on the feedback has been temporary put on hold due to more pressing matters. As of right now the team has the means to mount the camera above the target. The algorithm to determine the success of a launch is completed. The integration of the piezo devices and the camera is yet to be completed. Also the timing of the camera with respect to the ball launch and piezo devices needs to be completed. The cost estimate of the feedback system in the project proposal has been accurate. Until the launcher mounting issues are resolved progress on the feedback system is put on hold. The preliminary design of the launcher mount has been completed. The launcher mounting needs to be built and tested. In the previous report no considerations for the cost of the mounting was addressed. All the materials to build the mount have been purchased and came to $ The mount should be built by April 2 nd. The learning algorithm cannot proceed further until the rest of the system is integrated. Both Newton-Raphson and Schröder methods were derived and simulated based on our physics model of the ball trajectory. The Schröder algorithm was chosen to be implemented in the final machine due to its increased efficiency. The simulated results show a worst case scenario of four tries to hit the target. This is well within the proposed goal of hitting the target within eight tries. However, tuning still needs to be done after the algorithm is integrated, to account for unexpected gains and offsets. The algorithm is still based only on MATLAB/Simulink and has not incurred any additional costs. A new schedule has been developed based on our current progress, and is shown in Figure

23 Figure 22 Schedule 21

24 Bibliography 1. Franklin, G.F., J.D. Powell, and A. Emami-Naeini, Feedback Control of Dynamic Systems, 4th Edition, Addison-Wesley, Weisstein, Eric W. Drag Coefficient. Internet. (2005) Available: Feb Wen, John T. ECSE 4460 Control System Design, Spring Internet. (2005) Available: Feb Ball-Shooting Burp Gun. Internet. (2005) Available: Feb DC Motor Specifications Sheet. Internet. (2002) Available: Feb Root-Finding. Internet. (2004) Available: Feb The Proportional Valve. Internet. (2005) Available: Feb

25 Appix A.1: frictionexp.m % Script to obtain data for friction identification % Written by: Vinay Shah 2/25/05 voltagelist=[ ]; clear data; for i=1:length(voltagelist) A = voltagelist(i) for j=1:5 setparam(tg,21,sign(a)*10); % set 10 volt pulse start(tg); pause(1.5); % pulse duration of 1.5 seconds setparam(tg,21,a); pause(20); stop(tg); setparam(tg,21,0); pause(1); temp = tg.outputlog(:,1); size(temp) data(i,j,:) = temp(1001:20000); display('set position and press a key...'); reset motor pos pause; save(['panmotor',num2str(a),'.mat'],'voltagelist','data') %save often in case MATLAB crashes A.2: graphvelocity.m %Generate velocity time history curves for both pan and tilt axis %Written by: Vinay Shah 3/28/05 filelist ={'panpositive', 'pannegative', 'tiltpositive', 'tiltnegative'}; titlelist ={'Pan Motor', 'Tiltmotor'}; for k=1:4 load(filelist{k}); figure(2+ ceil(k/2)) hold on clear ssvalues; clear torques; for i = 1:length(voltagelist) r = rand; g = rand; b = rand; thetadot = 1000*diff(mean(squeeze(data(i,:,:)))); [fa, fb] = butter(12,.065); 23

26 output = filter(fa,fb, thetadot); ssvalues(i) = output(length(output)); torques(i) = voltagelist(i) * 4*6.3*.0436*0.1; plot(output,'color',[r,g,b],'linewidth',2); if ~mod(2,2) ylabel('velocity (rads/sec)') xlabel('time (ms)'); title(['friction Identification: ', titlelist{ceil(k/2)}]); hold off; A.3: frictionanalysis.m % Create torque versus steady state velocity graphs % Written by: Vinay Shah 3/29/05 figure(1) hold on load panpositive; [p1,s1]=polyfit(ssvalues,torques,1); lxpoint(1) = ssvalues(1); lxpoint(2) = ssvalues(length(ssvalues)); lypoint(1) = p1(1)*lxpoint(1) + p1(2); lypoint(2) = p1(1)*lxpoint(2) + p1(2); plot(lxpoint,lypoint) plot(ssvalues,torques,'xg'); disp(['pan Positive Viscous friction : ',num2str(p1(1))]); disp(['pan Positive Coulomb friction : ',num2str(p1(2))]) load pannegative; [p2,s2]=polyfit(ssvalues,torques,1); lxpoint(1) = ssvalues(1); lxpoint(2) = ssvalues(length(ssvalues)); lypoint(1) = p2(1)*lxpoint(1) + p2(2); lypoint(2) = p2(1)*lxpoint(2) + p2(2); plot(lxpoint,lypoint) plot(ssvalues,torques,'xr'); disp(['pan Negative Viscous friction : ',num2str(p2(1))]); disp(['pan Negative Coulomb friction : ',num2str(p2(2))]) lxpoint(1) = 0; lxpoint(2) = 0; lypoint(1) = p1(2); lypoint(2) = p2(2); plot(lxpoint,lypoint) xlabel('velocity (rads/sec)'); ylabel('torque (N*m)'); title('friction Indentification: Pan Motor') 24

27 figure(2); hold on load tiltpositive; [p2,s2]=polyfit(ssvalues,torques,1); lxpoint(1) = ssvalues(1); lxpoint(2) = ssvalues(length(ssvalues)); lypoint(1) = p2(1)*lxpoint(1) + p2(2); lypoint(2) = p2(1)*lxpoint(2) + p2(2); plot(lxpoint,lypoint) plot(ssvalues,torques,'xg'); disp(['tilt Positive Viscous friction : ',num2str(p2(1))]); disp(['tilt Positive Coulomb friction : ',num2str(p2(2))]); load tiltnegative; [p1,s1]=polyfit(ssvalues,torques,1); lxpoint(1) = ssvalues(1); lxpoint(2) = ssvalues(length(ssvalues)); lypoint(1) = p1(1)*lxpoint(1) + p1(2); lypoint(2) = p1(1)*lxpoint(2) + p1(2); plot(lxpoint,lypoint) plot(ssvalues,torques,'xr'); disp(['tilt Negative Viscous friction : ',num2str(p1(1))]); disp(['tilt Negative Coulomb friction : ',num2str(p1(2))]); xlabel('velocity (rads/sec)'); ylabel('torque (N*m)'); title('friction Indentification: Tilt Motor') lxpoint(1) = 0; lxpoint(2) = 0; lypoint(1) = p1(2); lypoint(2) = p2(2); plot(lxpoint,lypoint) A.4: paramiden.m % Parameter Identification Script % Written by: Vinay Shah 3/25/2005 % Model Parameters N = 4*6.3; Kt =.0436; Ki = 0.1; Jl = ; Jm = 1.6e-6; Bveff = 1.57e-3; Bceff =.078; m =.045; g = -9.81; l = 0.02; Jeff = Jl+ N*N*Jm; 25

28 % Actual values of parameters a1-a4 A1 = Bveff/Jeff A2 = Bceff/Jeff A3 = Kt*Ki*N/Jeff A4 = m*g*l/jeff %excite system with specific input sim('pantilt'); %determine velocity data from position data ts = 1/1000; avetheta = data; velocities = diff(avetheta)/ts; [b,a] = butter(12,.065); fvel = filter(b,a,velocities); % parameter identification algorithm thetadots = fvel; thetas = avetheta; thetadot0 = thetadots(1:length(thetadots)-1); thetadot1 = thetadots(2:length(thetadots)); voltagelist = voltage(3:length(voltage)); theta0 = thetas(2:length(thetas)-1); theta1 = thetas(3:length(thetas)); b = -thetadot0.^2 + thetadot1.^2; A = zeros(length(thetadots)-1,4); A(:,1) = -ts*(thetadot1.^2 + thetadot0.^2); A(:,2) = -ts*(abs(thetadot1) + abs(thetadot0)); A(:,3) = 2*(voltagelist.*(theta1 - theta0)); A(:,4) = -2*(cos(theta1) - cos(theta0)); %calculate experimentally determined values of parameters a1-a4 xvars = pinv(a)*b %check the validity of these values eigenvaluesofa = eig(a'*a) conditionofa = cond(a) 26

29 A.5: Processing Algorithm Target Area Camera Image of Target Binarization Location of Target Center of Target Ball hits piezo device Camera Color image of ball location Binarization Noise Reduction Center of Ball Inside target Comparison Successful Unsuccessful Convert ball location to world coordinates Learning Algorithm 27

30 A.6: Feedback System Camera Ball Lands Piezo Devices Amplifier XPC Target Laptop Frame Learning Algorithm Coordinates Image Processing A.7: Feedback MATLAB Code function D=thresh(image,k1,k2) %%image is rgb %%set k1 and k2 to adjust for outside interference %%k1+k2=2, k1 increases background, k2 increases foreground %%returns bilevel image global s; image=rgb2gray(image); %%convert to greyscale s=size(image); m0=50; %%initial guesses m1=125; Tp=200; T=87; while(tp~=t) %%interative algorithm to find threshold Tp=T; fore=0; back=0; f=0; b=0; for(i=1:s(1)) for(j=1:s(2)) V=double(image(i,j)); if(image(i,j)<=t) fore=fore+v; 28

31 f=f+1; else back=back+v; b=b+1; m0=ceil(fore/f); m1=ceil(back/b); T=ceil((k1*m1+k2*m0)/2); for(i=1:s(1)) %%thresholding for(j=1:s(2)) if(image(i,j)<t) image(i,j)=1; else image(i,j)=0; D=image; function C=find_center(image) %%image is bilevel %%1 coresponds to target, 0 to background %%output C(1) coresponds to y coordinate C(2) to x in image plane of centroid (physical %%plane conversion to polar coordinates is necessary) global center; %%initial variables global s; r=1; t=1; %%find locations of all foreground pixels for(i=1:s(1)) for(j=1:s(2)) if(image(i,j)==1) y(r)=i; x(t)=j; r=r+1; t=t+1; 29

32 %%calculate centroids center(1)=sum(y)/length(y); center(2)=sum(x)/length(x); C=center; function K=center_ball(image) %%finds the center of the ball by binarizing the image based on color %%threshold values should be found by inspecting histograms of the ball and %%of the background global s; new_image=zeros(s(1),s(2)); for(i=1:s(1)) %%detect color and binarize the image for(j=1:s(2)) if(image(i,j,1)>150) if(image(i,j,2)<170 & image(i,j,2)>95) if(image(i,j,3)<100) new_image(i,j)=1; %%eliminate noise new_image=bwmorph(new_image,'erode',2); new_image=bwmorph(new_image,'dilate',3); K=find_center(new_image); %%find centroid of ball function distance(bitarget,image) %%determines if the shot is sucessful, if not returns the error in %%pixel distances %%bitarget is a bi-level image of target %%image is image recieved by camera centerball=center_ball(image); %%find center of ball centertarget=find_center(bitarget); %%find center of target Cy=floor(centerball(1)); %%round values of ball location to integers Cx=floor(centerball(2)); 30

33 %%test whether or not within targer if(max(bitarget(cy:cy+1,cx:cx+1))==1) display('target hit') else X=centerball(2)-centertarget(2); Y=centerball(1)-centertarget(1); display('target missed by'); X Y End A.8: Ball Trajectory Model A.9: la_newton-raphson.m %Learning Algorithm using Newton-Raphson method clear all; rd = 1.5; phid = -pi/4; maxdiffr = 0.045; maxdiffphi = 0.025; iterations = 0; Kz = 0.1; Kr = 0.1; Kphi = 0.1; 31

34 Vo = 4.767; h = 1.016; g = 9.8; theta1 = atan2((-h*(vo^2+g*h-(vo^4+2*vo^2*g*hrd^2*g^2)^(1/2))/(h^2+rd^2)+g)/vo/((vo^2+g*h-(vo^4+2*vo^2*g*hrd^2*g^2)^(1/2))/(h^2+rd^2))^(1/2),((vo^2+g*h-(vo^4+2*vo^2*g*hrd^2*g^2)^(1/2))/(h^2+rd^2))^(1/2)*rd/vo); theta2 = phid; while(1) iterations = iterations + 1; dfrdtheta1 = (Vo*cos(theta1)+1/(Vo^2*sin(theta1)^2+2*g*h)^(1/2)*Vo^2*sin(theta1)*cos (theta1))*vo*cos(theta1)/g- (Vo*sin(theta1)+(Vo^2*sin(theta1)^2+2*g*h)^(1/2))*Vo*sin(theta1)/g; dfphidtheta2 = 1; sim('ballmotioncylind'); hold on; grid off; figure(1); title('newton-raphson method'); xlabel('r(m)'); ylabel('z(m)'); plot(r,z); figure(2); title('newton-raphson method'); polar(phi,r); if(abs(rd-finalr) > maxdiffr) theta1 = theta1 + (rd - finalr)/(dfrdtheta1); ; if(abs(phid-finalphi) > maxdiffphi) theta2 = theta2 + (phid - finalphi); ; if((abs(rd-finalr) < maxdiffr) & (abs(phid-finalphi) < maxdiffphi)) break; ; ; hold off A.10: la_schroder.m clear all; rd = 1.5; phid = -pi/4; maxdiffr = 0.045; maxdiffphi = 0.025; 32

35 iterations = 0; Kz = 0.1; Kr = 0.1; Kphi = 0.1; Vo = 4.767; ; h = 1.016; ; g = 9.8; theta1 = atan2((-h*(vo^2+g*h-(vo^4+2*vo^2*g*hrd^2*g^2)^(1/2))/(h^2+rd^2)+g)/vo/((vo^2+g*h-(vo^4+2*vo^2*g*hrd^2*g^2)^(1/2))/(h^2+rd^2))^(1/2),((vo^2+g*h-(vo^4+2*vo^2*g*hrd^2*g^2)^(1/2))/(h^2+rd^2))^(1/2)*rd/vo); theta2 = phid; while(1) iterations = iterations + 1; dfrdtheta1 = (Vo*cos(theta1)+1/(Vo^2*sin(theta1)^2+2*g*h)^(1/2)*Vo^2*sin(theta1)*cos (theta1))*vo*cos(theta1)/g- (Vo*sin(theta1)+(Vo^2*sin(theta1)^2+2*g*h)^(1/2))*Vo*sin(theta1)/g; d2frd2theta1 = (-Vo*sin(theta1)- 1/(Vo^2*sin(theta1)^2+2*g*h)^(3/2)*Vo^4*sin(theta1)^2*cos(theta1)^2+1/( Vo^2*sin(theta1)^2+2*g*h)^(1/2)*Vo^2*cos(theta1)^2-1/(Vo^2*sin(theta1)^2+2*g*h)^(1/2)*Vo^2*sin(theta1)^2)*Vo*cos(theta1)/g - 2*(Vo*cos(theta1)+1/(Vo^2*sin(theta1)^2+2*g*h)^(1/2)*Vo^2*sin(theta1)*c os(theta1))*vo*sin(theta1)/g- (Vo*sin(theta1)+(Vo^2*sin(theta1)^2+2*g*h)^(1/2))*Vo*cos(theta1)/g; dfphidtheta2 = 1; sim('ballmotioncylind'); hold on; figure(1); title('schroder'); xlabel('r(m)'); ylabel('z(m)'); plot(r,z); figure(2); title('schroder'); polar(phi,r); if(abs(rd-finalr) > maxdiffr) theta1 = theta1 + (rd - finalr)*(dfrdtheta1)/((dfrdtheta1)^2+(rd - finalr)*(d2frd2theta1)); ; if(abs(phid-finalphi) > maxdiffphi) theta2 = theta2 + (phid - finalphi); ; if((abs(rd-finalr) < maxdiffr) & (abs(phid-finalphi) < maxdiffphi)) break; ; ; hold off 33

DOUBLE ARM JUGGLING SYSTEM Progress Presentation ECSE-4962 Control Systems Design

DOUBLE ARM JUGGLING SYSTEM Progress Presentation ECSE-4962 Control Systems Design DOUBLE ARM JUGGLING SYSTEM Progress Presentation ECSE-4962 Control Systems Design Group Members: John Kua Trinell Ball Linda Rivera Introduction Where are we? Bulk of Design and Build Complete Testing

More information

Positioning Servo Design Example

Positioning Servo Design Example Positioning Servo Design Example 1 Goal. The goal in this design example is to design a control system that will be used in a pick-and-place robot to move the link of a robot between two positions. Usually

More information

Digital Control Semester Project

Digital Control Semester Project Digital Control Semester Project Part I: Transform-Based Design 1 Introduction For this project you will be designing a digital controller for a system which consists of a DC motor driving a shaft with

More information

Projectile Motion. x = v ox t (1)

Projectile Motion. x = v ox t (1) Projectile Motion Theory Projectile motion is the combination of different motions in the x and y directions. In the x direction, which is taken as parallel to the surface of the earth, the projectile

More information

The basic principle to be used in mechanical systems to derive a mathematical model is Newton s law,

The basic principle to be used in mechanical systems to derive a mathematical model is Newton s law, Chapter. DYNAMIC MODELING Understanding the nature of the process to be controlled is a central issue for a control engineer. Thus the engineer must construct a model of the process with whatever information

More information

Manufacturing Equipment Control

Manufacturing Equipment Control QUESTION 1 An electric drive spindle has the following parameters: J m = 2 1 3 kg m 2, R a = 8 Ω, K t =.5 N m/a, K v =.5 V/(rad/s), K a = 2, J s = 4 1 2 kg m 2, and K s =.3. Ignore electrical dynamics

More information

Experiment # 5 5. Coupled Water Tanks

Experiment # 5 5. Coupled Water Tanks Experiment # 5 5. Coupled Water Tanks 5.. Objectives The Coupled-Tank plant is a Two-Tank module consisting of a pump with a water basin and two tanks. The two tanks are mounted on the front plate such

More information

Motion on a linear air track

Motion on a linear air track Motion on a linear air track Introduction During the early part of the 17 th century, Galileo experimentally examined the concept of acceleration. One of his goals was to learn more about freely falling

More information

SRV02-Series Rotary Experiment # 1. Position Control. Student Handout

SRV02-Series Rotary Experiment # 1. Position Control. Student Handout SRV02-Series Rotary Experiment # 1 Position Control Student Handout SRV02-Series Rotary Experiment # 1 Position Control Student Handout 1. Objectives The objective in this experiment is to introduce the

More information

Mechatronics Engineering. Li Wen

Mechatronics Engineering. Li Wen Mechatronics Engineering Li Wen Bio-inspired robot-dc motor drive Unstable system Mirko Kovac,EPFL Modeling and simulation of the control system Problems 1. Why we establish mathematical model of the control

More information

State Feedback Controller for Position Control of a Flexible Link

State Feedback Controller for Position Control of a Flexible Link Laboratory 12 Control Systems Laboratory ECE3557 Laboratory 12 State Feedback Controller for Position Control of a Flexible Link 12.1 Objective The objective of this laboratory is to design a full state

More information

General Physics I Lab (PHYS-2011) Experiment MECH-1: Projectile Motion

General Physics I Lab (PHYS-2011) Experiment MECH-1: Projectile Motion MECH-1: Projectile Motion Page 1 of 7 1 EQUIPMENT General Physics I Lab (PHYS-2011) Experiment MECH-1: Projectile Motion 1 Mini Launcher ME-6825 1 Time of Flight Accessory ME-6810 1 Phone Jack Extender

More information

Modeling Airplane Wings

Modeling Airplane Wings Modeling Airplane Wings Lauren Ault Physics Department, The College of Wooster, Wooster, Ohio 9 May 5, 000 Abstract: An air gyroscope is used to determine the nature of the viscous force of a sphere floating

More information

FEEDBACK CONTROL SYSTEMS

FEEDBACK CONTROL SYSTEMS FEEDBAC CONTROL SYSTEMS. Control System Design. Open and Closed-Loop Control Systems 3. Why Closed-Loop Control? 4. Case Study --- Speed Control of a DC Motor 5. Steady-State Errors in Unity Feedback Control

More information

Index. Index. More information. in this web service Cambridge University Press

Index. Index. More information.  in this web service Cambridge University Press A-type elements, 4 7, 18, 31, 168, 198, 202, 219, 220, 222, 225 A-type variables. See Across variable ac current, 172, 251 ac induction motor, 251 Acceleration rotational, 30 translational, 16 Accumulator,

More information

Energy Problem Solving Techniques.

Energy Problem Solving Techniques. 1 Energy Problem Solving Techniques www.njctl.org 2 Table of Contents Introduction Gravitational Potential Energy Problem Solving GPE, KE and EPE Problem Solving Conservation of Energy Problem Solving

More information

Purpose: Materials: WARNING! Section: Partner 2: Partner 1:

Purpose: Materials: WARNING! Section: Partner 2: Partner 1: Partner 1: Partner 2: Section: PLEASE NOTE: You will need this particular lab report later in the semester again for the homework of the Rolling Motion Experiment. When you get back this graded report,

More information

Appendix A: Exercise Problems on Classical Feedback Control Theory (Chaps. 1 and 2)

Appendix A: Exercise Problems on Classical Feedback Control Theory (Chaps. 1 and 2) Appendix A: Exercise Problems on Classical Feedback Control Theory (Chaps. 1 and 2) For all calculations in this book, you can use the MathCad software or any other mathematical software that you are familiar

More information

General procedure for formulation of robot dynamics STEP 1 STEP 3. Module 9 : Robot Dynamics & controls

General procedure for formulation of robot dynamics STEP 1 STEP 3. Module 9 : Robot Dynamics & controls Module 9 : Robot Dynamics & controls Lecture 32 : General procedure for dynamics equation forming and introduction to control Objectives In this course you will learn the following Lagrangian Formulation

More information

Application Note #3413

Application Note #3413 Application Note #3413 Manual Tuning Methods Tuning the controller seems to be a difficult task to some users; however, after getting familiar with the theories and tricks behind it, one might find the

More information

2.004 Dynamics and Control II Spring 2008

2.004 Dynamics and Control II Spring 2008 MIT OpenCourseWare http://ocw.mit.edu 2.004 Dynamics and Control II Spring 2008 For information about citing these materials or our Terms of Use, visit: http://ocw.mit.edu/terms. Massachusetts Institute

More information

E X P E R I M E N T 11

E X P E R I M E N T 11 E X P E R I M E N T 11 Conservation of Angular Momentum Produced by the Physics Staff at Collin College Copyright Collin College Physics Department. All Rights Reserved. University Physics, Exp 11: Conservation

More information

YTÜ Mechanical Engineering Department

YTÜ Mechanical Engineering Department YTÜ Mechanical Engineering Department Lecture of Special Laboratory of Machine Theory, System Dynamics and Control Division Coupled Tank 1 Level Control with using Feedforward PI Controller Lab Date: Lab

More information

Ballistic Pendulum. Caution

Ballistic Pendulum. Caution Ballistic Pendulum Caution In this experiment a steel ball is projected horizontally across the room with sufficient speed to injure a person. Be sure the line of fire is clear before firing the ball,

More information

Projectile Motion (Photogates)

Projectile Motion (Photogates) Projectile Motion (Photogates) Name Section Theory Projectile motion is the combination of different motions in the x and y direction. In the x direction, which is taken as parallel to the surface of the

More information

ECSE 4962 Control Systems Design. A Brief Tutorial on Control Design

ECSE 4962 Control Systems Design. A Brief Tutorial on Control Design ECSE 4962 Control Systems Design A Brief Tutorial on Control Design Instructor: Professor John T. Wen TA: Ben Potsaid http://www.cat.rpi.edu/~wen/ecse4962s04/ Don t Wait Until The Last Minute! You got

More information

Lab 3: Quanser Hardware and Proportional Control

Lab 3: Quanser Hardware and Proportional Control Lab 3: Quanser Hardware and Proportional Control The worst wheel of the cart makes the most noise. Benjamin Franklin 1 Objectives The goal of this lab is to: 1. familiarize you with Quanser s QuaRC tools

More information

Lab 8: Ballistic Pendulum

Lab 8: Ballistic Pendulum Lab 8: Ballistic Pendulum Caution In this experiment a steel ball is projected horizontally across the room with sufficient speed to injure a person. Be sure the line of fire is clear before firing the

More information

Lab 3: Model based Position Control of a Cart

Lab 3: Model based Position Control of a Cart I. Objective Lab 3: Model based Position Control of a Cart The goal of this lab is to help understand the methodology to design a controller using the given plant dynamics. Specifically, we would do position

More information

MEAM 510 Fall 2011 Bruce D. Kothmann

MEAM 510 Fall 2011 Bruce D. Kothmann Balancing g Robot Control MEAM 510 Fall 2011 Bruce D. Kothmann Agenda Bruce s Controls Resume Simple Mechanics (Statics & Dynamics) of the Balancing Robot Basic Ideas About Feedback & Stability Effects

More information

AP Physics C - Mechanics

AP Physics C - Mechanics Slide 1 / 84 Slide 2 / 84 P Physics C - Mechanics Energy Problem Solving Techniques 2015-12-03 www.njctl.org Table of Contents Slide 3 / 84 Introduction Gravitational Potential Energy Problem Solving GPE,

More information

Example: DC Motor Speed Modeling

Example: DC Motor Speed Modeling Page 1 of 5 Example: DC Motor Speed Modeling Physical setup and system equations Design requirements MATLAB representation and open-loop response Physical setup and system equations A common actuator in

More information

Inverted Pendulum. Objectives

Inverted Pendulum. Objectives Inverted Pendulum Objectives The objective of this lab is to experiment with the stabilization of an unstable system. The inverted pendulum problem is taken as an example and the animation program gives

More information

Lecture 17 - Gyroscopes

Lecture 17 - Gyroscopes Lecture 17 - Gyroscopes A Puzzle... We have seen throughout class that the center of mass is a very powerful tool for evaluating systems. However, don t let yourself get carried away with how useful it

More information

SRV02-Series Rotary Experiment # 7. Rotary Inverted Pendulum. Student Handout

SRV02-Series Rotary Experiment # 7. Rotary Inverted Pendulum. Student Handout SRV02-Series Rotary Experiment # 7 Rotary Inverted Pendulum Student Handout SRV02-Series Rotary Experiment # 7 Rotary Inverted Pendulum Student Handout 1. Objectives The objective in this experiment is

More information

Lab 2. Projectile Motion

Lab 2. Projectile Motion Lab 2. Projectile Motion Goals To determine the launch speed of a projectile and its uncertainty by measuring how far it travels horizontally before landing on the floor (called the range) when launched

More information

Inverted Pendulum System

Inverted Pendulum System Introduction Inverted Pendulum System This lab experiment consists of two experimental procedures, each with sub parts. Experiment 1 is used to determine the system parameters needed to implement a controller.

More information

PHY 221 Lab 7 Work and Energy

PHY 221 Lab 7 Work and Energy PHY 221 Lab 7 Work and Energy Name: Partners: Goals: Before coming to lab, please read this packet and do the prelab on page 13 of this handout. Note: originally, Lab 7 was momentum and collisions. The

More information

Laboratory 11 Control Systems Laboratory ECE3557. State Feedback Controller for Position Control of a Flexible Joint

Laboratory 11 Control Systems Laboratory ECE3557. State Feedback Controller for Position Control of a Flexible Joint Laboratory 11 State Feedback Controller for Position Control of a Flexible Joint 11.1 Objective The objective of this laboratory is to design a full state feedback controller for endpoint position control

More information

Laboratory Exercise 1 DC servo

Laboratory Exercise 1 DC servo Laboratory Exercise DC servo Per-Olof Källén ø 0,8 POWER SAT. OVL.RESET POS.RESET Moment Reference ø 0,5 ø 0,5 ø 0,5 ø 0,65 ø 0,65 Int ø 0,8 ø 0,8 Σ k Js + d ø 0,8 s ø 0 8 Off Off ø 0,8 Ext. Int. + x0,

More information

Ballistic Pendulum. Equipment. Introduction. Setup

Ballistic Pendulum. Equipment. Introduction. Setup 35 Ballistic Pendulum 35 - Page 1 of 5 Equipment Ballistic Pendulum 1 Rotary Motion Sensor PS-2120A 2 Photogate Head ME-9498A 1 Mounting Bracket ME-6821A 1 Large Table Clamp ME-9472 1 90 cm rod ME-8738

More information

Lab 6a: Pole Placement for the Inverted Pendulum

Lab 6a: Pole Placement for the Inverted Pendulum Lab 6a: Pole Placement for the Inverted Pendulum Idiot. Above her head was the only stable place in the cosmos, the only refuge from the damnation of the Panta Rei, and she guessed it was the Pendulum

More information

Conservation of Momentum

Conservation of Momentum Learning Goals Conservation of Momentum After you finish this lab, you will be able to: 1. Use Logger Pro to analyze video and calculate position, velocity, and acceleration. 2. Use the equations for 2-dimensional

More information

MEAM 510 Fall 2012 Bruce D. Kothmann

MEAM 510 Fall 2012 Bruce D. Kothmann Balancing g Robot Control MEAM 510 Fall 2012 Bruce D. Kothmann Agenda Bruce s Controls Resume Simple Mechanics (Statics & Dynamics) of the Balancing Robot Basic Ideas About Feedback & Stability Effects

More information

Week 14 The Simple Pendulum

Week 14 The Simple Pendulum Week 14 The Simple Pendulum 1. Scope 1.1 Goal Conduct experiment to study the simple harmonic motion of an oscillatory pendulum and analyze and interpret the data 1.2 Units of measurement to use United

More information

Experiment AM Angular Momentum

Experiment AM Angular Momentum Experiment AM Angular Momentum Introduction If an object, e.g., a heavy ball, comes straight at you and you catch it, you may stagger back while exerting the impulse -- some force for some time -- needed

More information

12-Nov-17 PHYS Inelastic Collision. To study the laws of conservation of linear momentum and energy in a completely inelastic collision.

12-Nov-17 PHYS Inelastic Collision. To study the laws of conservation of linear momentum and energy in a completely inelastic collision. Objectives Inelastic Collision To study the laws of conservation of linear momentum and energy in a completely inelastic collision. Introduction If no net external force acts on a system of particles,

More information

Example: Modeling DC Motor Position Physical Setup System Equations Design Requirements MATLAB Representation and Open-Loop Response

Example: Modeling DC Motor Position Physical Setup System Equations Design Requirements MATLAB Representation and Open-Loop Response Page 1 of 5 Example: Modeling DC Motor Position Physical Setup System Equations Design Requirements MATLAB Representation and Open-Loop Response Physical Setup A common actuator in control systems is the

More information

EXPERIMENT 7: ANGULAR KINEMATICS AND TORQUE (V_3)

EXPERIMENT 7: ANGULAR KINEMATICS AND TORQUE (V_3) TA name Lab section Date TA Initials (on completion) Name UW Student ID # Lab Partner(s) EXPERIMENT 7: ANGULAR KINEMATICS AND TORQUE (V_3) 121 Textbook Reference: Knight, Chapter 13.1-3, 6. SYNOPSIS In

More information

Rube-Goldberg Device. Team #1; A1, 4/28/10. Matt Burr, Kayla Stone, Blake Hanson, Alex Denton

Rube-Goldberg Device. Team #1; A1, 4/28/10. Matt Burr, Kayla Stone, Blake Hanson, Alex Denton Rube-Goldberg Device Team #1; A1, 4/28/10 Matt Burr, Kayla Stone, Blake Hanson, Alex Denton Introduction The main goal of our team when creating the Rube Goldberg machine was to construct an inefficient

More information

Lab 5: Projectile Motion

Lab 5: Projectile Motion Concepts to explore Scalars vs. vectors Projectiles Parabolic trajectory As you learned in Lab 4, a quantity that conveys information about magnitude only is called a scalar. However, when a quantity,

More information

Lab 10: Ballistic Pendulum

Lab 10: Ballistic Pendulum Lab Section (circle): Day: Monday Tuesday Time: 8:00 9:30 1:10 2:40 Lab 10: Ballistic Pendulum Name: Partners: Pre-Lab You are required to finish this section before coming to the lab it will be checked

More information

Project Lab Report. Michael Hall. Hao Zhu. Neil Nevgi. Station 6. Ta: Yan Cui

Project Lab Report. Michael Hall. Hao Zhu. Neil Nevgi. Station 6. Ta: Yan Cui Project Lab Report Michael Hall Hao Zhu Neil Nevgi Station 6 Ta: Yan Cui Nov. 12 th 2012 Table of Contents: Executive Summary 3 Modeling Report.4-7 System Identification 7-11 Control Design..11-15 Simulation

More information

Lab I. 2D Motion. 1 Introduction. 2 Theory. 2.1 scalars and vectors LAB I. 2D MOTION 15

Lab I. 2D Motion. 1 Introduction. 2 Theory. 2.1 scalars and vectors LAB I. 2D MOTION 15 LAB I. 2D MOTION 15 Lab I 2D Motion 1 Introduction In this lab we will examine simple two-dimensional motion without acceleration. Motion in two dimensions can often be broken up into two separate one-dimensional

More information

Guidance for Writing Lab Reports for PHYS 233:

Guidance for Writing Lab Reports for PHYS 233: Guidance for Writing Lab Reports for PHYS 233: The following pages have a sample lab report that is a model of what we expect for each of your lab reports in PHYS 233. It is written for a lab experiment

More information

Feedback Control of Linear SISO systems. Process Dynamics and Control

Feedback Control of Linear SISO systems. Process Dynamics and Control Feedback Control of Linear SISO systems Process Dynamics and Control 1 Open-Loop Process The study of dynamics was limited to open-loop systems Observe process behavior as a result of specific input signals

More information

LAB 3: WORK AND ENERGY

LAB 3: WORK AND ENERGY 1 Name Date Lab Day/Time Partner(s) Lab TA (CORRECTED /4/05) OBJECTIVES LAB 3: WORK AND ENERGY To understand the concept of work in physics as an extension of the intuitive understanding of effort. To

More information

Lab I. 2D Motion. 1 Introduction. 2 Theory. 2.1 scalars and vectors LAB I. 2D MOTION 15

Lab I. 2D Motion. 1 Introduction. 2 Theory. 2.1 scalars and vectors LAB I. 2D MOTION 15 LAB I. 2D MOTION 15 Lab I 2D Motion 1 Introduction In this lab we will examine simple two-dimensional motion without acceleration. Motion in two dimensions can often be broken up into two separate one-dimensional

More information

PHY 221 Lab 9 Work and Energy

PHY 221 Lab 9 Work and Energy PHY 221 Lab 9 Work and Energy Name: Partners: Before coming to lab, please read this packet and do the prelab on page 13 of this handout. Goals: While F = ma may be one of the most important equations

More information

ECE 5670/6670 Lab 8. Torque Curves of Induction Motors. Objectives

ECE 5670/6670 Lab 8. Torque Curves of Induction Motors. Objectives ECE 5670/6670 Lab 8 Torque Curves of Induction Motors Objectives The objective of the lab is to measure the torque curves of induction motors. Acceleration experiments are used to reconstruct approximately

More information

9.1 Harmonic Motion. Motion in cycles. linear motion - motion that goes from one place to another without repeating.

9.1 Harmonic Motion. Motion in cycles. linear motion - motion that goes from one place to another without repeating. 9.1 Harmonic Motion A bicyclist pedaling past you on the street moves in linear motion. Linear motion gets us from one place to another (Figure 9.1A). This chapter is about another kind of motion called

More information

Department of Mechanical Engineering

Department of Mechanical Engineering Department of Mechanical Engineering 2.010 CONTROL SYSTEMS PRINCIPLES Laboratory 2: Characterization of the Electro-Mechanical Plant Introduction: It is important (for future lab sessions) that we have

More information

Vacuum Kelvin Force Probe Research Richard Williams August 1st 2008

Vacuum Kelvin Force Probe Research Richard Williams August 1st 2008 Vacuum Kelvin Force Probe Research Richard Williams August 1st 2008 Introduction Kelvin Force Probe Microscopy is an analytical method to measure the contact potential difference between a reference material

More information

Stepping Motors. Chapter 11 L E L F L D

Stepping Motors. Chapter 11 L E L F L D Chapter 11 Stepping Motors In the synchronous motor, the combination of sinusoidally distributed windings and sinusoidally time varying current produces a smoothly rotating magnetic field. We can eliminate

More information

6) Motors and Encoders

6) Motors and Encoders 6) Motors and Encoders Electric motors are by far the most common component to supply mechanical input to a linear motion system. Stepper motors and servo motors are the popular choices in linear motion

More information

Double Inverted Pendulum (DBIP)

Double Inverted Pendulum (DBIP) Linear Motion Servo Plant: IP01_2 Linear Experiment #15: LQR Control Double Inverted Pendulum (DBIP) All of Quanser s systems have an inherent open architecture design. It should be noted that the following

More information

Quanser NI-ELVIS Trainer (QNET) Series: QNET Experiment #02: DC Motor Position Control. DC Motor Control Trainer (DCMCT) Student Manual

Quanser NI-ELVIS Trainer (QNET) Series: QNET Experiment #02: DC Motor Position Control. DC Motor Control Trainer (DCMCT) Student Manual Quanser NI-ELVIS Trainer (QNET) Series: QNET Experiment #02: DC Motor Position Control DC Motor Control Trainer (DCMCT) Student Manual Table of Contents 1 Laboratory Objectives1 2 References1 3 DCMCT Plant

More information

Lab 10: Harmonic Motion and the Pendulum

Lab 10: Harmonic Motion and the Pendulum Lab 10 Harmonic Motion and the Pendulum 119 Name Date Partners Lab 10: Harmonic Motion and the Pendulum OVERVIEW A body is said to be in a position of stable equilibrium if, after displacement in any direction,

More information

Digital Pendulum Control Experiments

Digital Pendulum Control Experiments EE-341L CONTROL SYSTEMS LAB 2013 Digital Pendulum Control Experiments Ahmed Zia Sheikh 2010030 M. Salman Khalid 2010235 Suleman Belal Kazi 2010341 TABLE OF CONTENTS ABSTRACT...2 PENDULUM OVERVIEW...3 EXERCISE

More information

Robot Manipulator Control. Hesheng Wang Dept. of Automation

Robot Manipulator Control. Hesheng Wang Dept. of Automation Robot Manipulator Control Hesheng Wang Dept. of Automation Introduction Industrial robots work based on the teaching/playback scheme Operators teach the task procedure to a robot he robot plays back eecute

More information

Activity P24: Conservation of Linear and Angular Momentum (Photogate/Pulley System)

Activity P24: Conservation of Linear and Angular Momentum (Photogate/Pulley System) Name Class Date Activity P24: Conservation of Linear and Angular Momentum (Photogate/Pulley System) Concept DataStudio ScienceWorkshop (Mac) ScienceWorkshop (Win) Momentum P24 Linear Angular.DS P28 Cons

More information

DEVELOPMENT OF DROP WEIGHT IMPACT TEST MACHINE

DEVELOPMENT OF DROP WEIGHT IMPACT TEST MACHINE CHAPTER-8 DEVELOPMENT OF DROP WEIGHT IMPACT TEST MACHINE 8.1 Introduction The behavior of materials is different when they are subjected to dynamic loading [9]. The testing of materials under dynamic conditions

More information

Implementation Issues for the Virtual Spring

Implementation Issues for the Virtual Spring Implementation Issues for the Virtual Spring J. S. Freudenberg EECS 461 Embedded Control Systems 1 Introduction One of the tasks in Lab 4 is to attach the haptic wheel to a virtual reference position with

More information

Dynamics of Machines. Prof. Amitabha Ghosh. Department of Mechanical Engineering. Indian Institute of Technology, Kanpur. Module No.

Dynamics of Machines. Prof. Amitabha Ghosh. Department of Mechanical Engineering. Indian Institute of Technology, Kanpur. Module No. Dynamics of Machines Prof. Amitabha Ghosh Department of Mechanical Engineering Indian Institute of Technology, Kanpur Module No. # 07 Lecture No. # 01 In our previous lectures, you have noticed that we

More information

Millikan Oil Drop Experiment

Millikan Oil Drop Experiment Millikan Oil Drop Experiment Introduction The electronic charge, or electrical charge carried by an electron, is a fundamental constant in physics. During the years 1909 to 1913, R.A. Millikan used the

More information

MECH 3140 Final Project

MECH 3140 Final Project MECH 3140 Final Project Final presentation will be held December 7-8. The presentation will be the only deliverable for the final project and should be approximately 20-25 minutes with an additional 10

More information

Experiment P28: Conservation of Linear and Angular Momentum (Smart Pulley)

Experiment P28: Conservation of Linear and Angular Momentum (Smart Pulley) PASCO scientific Physics Lab Manual: P28-1 Experiment P28: Conservation of Linear and Angular Momentum (Smart Pulley) Concept Time SW Interface Macintosh File Windows File rotational motion 45 m 500 or

More information

PHYS 3324 Lab Millikan Oil Drop Experiment: Demonstration of the Quantization of Charge

PHYS 3324 Lab Millikan Oil Drop Experiment: Demonstration of the Quantization of Charge PHYS 3324 Lab Millikan Oil Drop Experiment: Demonstration of the Quantization of Charge Background reading Read the introduction below before answering the Prelab Questions Prelab Questions 1. A typical

More information

Ballistic Pendulum. Equipment- ballistic pendulum apparatus, 2 meter ruler, 30 cm ruler, blank paper, carbon paper, masking tape, scale PRECAUTION

Ballistic Pendulum. Equipment- ballistic pendulum apparatus, 2 meter ruler, 30 cm ruler, blank paper, carbon paper, masking tape, scale PRECAUTION Ballistic Pendulum Equipment- ballistic pendulum apparatus, 2 meter ruler, 30 cm ruler, blank paper, carbon paper, masking tape, scale PRECAUTION In this experiment a steel ball is projected horizontally

More information

Lab 5: Projectile Motion

Lab 5: Projectile Motion Lab 5 Projectile Motion 47 Name Date Partners Lab 5: Projectile Motion OVERVIEW We learn in our study of kinematics that two-dimensional motion is a straightforward application of onedimensional motion.

More information

Newton s Second Law Physics Lab V

Newton s Second Law Physics Lab V Newton s Second Law Physics Lab V Objective The Newton s Second Law experiment provides the student a hands on demonstration of forces in motion. A formulated analysis of forces acting on a dynamics cart

More information

ME 3210 Mechatronics II Laboratory Lab 4: DC Motor Characteristics

ME 3210 Mechatronics II Laboratory Lab 4: DC Motor Characteristics ME 3210 Mechatronics II Laboratory Lab 4: DC Motor Characteristics Introduction Often, due to budget constraints or convenience, engineers must use whatever tools are available to create new or improved

More information

Rotary Motion Servo Plant: SRV02. Rotary Experiment #11: 1-DOF Torsion. 1-DOF Torsion Position Control using QuaRC. Student Manual

Rotary Motion Servo Plant: SRV02. Rotary Experiment #11: 1-DOF Torsion. 1-DOF Torsion Position Control using QuaRC. Student Manual Rotary Motion Servo Plant: SRV02 Rotary Experiment #11: 1-DOF Torsion 1-DOF Torsion Position Control using QuaRC Student Manual Table of Contents 1. INTRODUCTION...1 2. PREREQUISITES...1 3. OVERVIEW OF

More information

Gravity Pre-Lab 1. Why do you need an inclined plane to measure the effects due to gravity?

Gravity Pre-Lab 1. Why do you need an inclined plane to measure the effects due to gravity? Lab Exercise: Gravity (Report) Your Name & Your Lab Partner s Name Due Date Gravity Pre-Lab 1. Why do you need an inclined plane to measure the effects due to gravity? 2. What are several advantage of

More information

Rotational Motion. Figure 1: Torsional harmonic oscillator. The locations of the rotor and fiber are indicated.

Rotational Motion. Figure 1: Torsional harmonic oscillator. The locations of the rotor and fiber are indicated. Rotational Motion 1 Purpose The main purpose of this laboratory is to familiarize you with the use of the Torsional Harmonic Oscillator (THO) that will be the subject of the final lab of the course on

More information

YTÜ Mechanical Engineering Department

YTÜ Mechanical Engineering Department YTÜ Mechanical Engineering Department Lecture of Special Laboratory of Machine Theory, System Dynamics and Control Division Coupled Tank 1 Level Control with using Feedforward PI Controller Lab Report

More information

Lecture 6: Control Problems and Solutions. CS 344R: Robotics Benjamin Kuipers

Lecture 6: Control Problems and Solutions. CS 344R: Robotics Benjamin Kuipers Lecture 6: Control Problems and Solutions CS 344R: Robotics Benjamin Kuipers But First, Assignment 1: Followers A follower is a control law where the robot moves forward while keeping some error term small.

More information

POWER SYSTEM STABILITY

POWER SYSTEM STABILITY LESSON SUMMARY-1:- POWER SYSTEM STABILITY 1. Introduction 2. Classification of Power System Stability 3. Dynamic Equation of Synchronous Machine Power system stability involves the study of the dynamics

More information

MASSACHUSETTS INSTITUTE OF TECHNOLOGY Physics Department

MASSACHUSETTS INSTITUTE OF TECHNOLOGY Physics Department MASSACHUSETTS INSTITUTE OF TECHNOLOGY Physics Department Physics 8.01T Fall Term 2004 Experiment 06: Work, Energy and the Harmonic Oscillator Purpose of the Experiment: In this experiment you allow a cart

More information

On my honor, I have neither given nor received unauthorized aid on this examination.

On my honor, I have neither given nor received unauthorized aid on this examination. Instructor(s): Field/inzler PHYSICS DEPATMENT PHY 2053 Final Exam April 27, 2013 Name (print, last first): Signature: On my honor, I have neither given nor received unauthorized aid on this examination.

More information

CHAPTER 1 Basic Concepts of Control System. CHAPTER 6 Hydraulic Control System

CHAPTER 1 Basic Concepts of Control System. CHAPTER 6 Hydraulic Control System CHAPTER 1 Basic Concepts of Control System 1. What is open loop control systems and closed loop control systems? Compare open loop control system with closed loop control system. Write down major advantages

More information

Acceleration and velocity are related and have a direct impact on the three basic parts of the CNC system.

Acceleration and velocity are related and have a direct impact on the three basic parts of the CNC system. Acceleration and velocity are related and have a direct impact on the three basic parts of the CNC system. ACCELERATION Acceleration is a change in velocity with respect to time. The term, in context of

More information

Name: Lab Partner: Section:

Name: Lab Partner: Section: Chapter 7 Energy Name: Lab Partner: Section: 7.1 Purpose In this experiment, energy and work will be explored. The relationship between total energy, kinetic energy and potential energy will be observed.

More information

Simple Harmonic Motion

Simple Harmonic Motion [International Campus Lab] Objective Investigate simple harmonic motion using an oscillating spring and a simple pendulum. Theory ----------------------------- Reference -------------------------- Young

More information

Motion in 1 Dimension. By Prof. Massimiliano Galeazzi, University of Miami

Motion in 1 Dimension. By Prof. Massimiliano Galeazzi, University of Miami Motion in 1 Dimension By Prof. Massimiliano Galeazzi, University of Miami When you throw a pebble straight up, how high does it go? How fast is it when it gets back? If you are in your car at a red light

More information

Trigonometry Basics. Which side is opposite? It depends on the angle. θ 2. Y is opposite to θ 1 ; Y is adjacent to θ 2.

Trigonometry Basics. Which side is opposite? It depends on the angle. θ 2. Y is opposite to θ 1 ; Y is adjacent to θ 2. Trigonometry Basics Basic Terms θ (theta) variable for any angle. Hypotenuse longest side of a triangle. Opposite side opposite the angle (θ). Adjacent side next to the angle (θ). Which side is opposite?

More information

Multivariable Control Laboratory experiment 2 The Quadruple Tank 1

Multivariable Control Laboratory experiment 2 The Quadruple Tank 1 Multivariable Control Laboratory experiment 2 The Quadruple Tank 1 Department of Automatic Control Lund Institute of Technology 1. Introduction The aim of this laboratory exercise is to study some different

More information

Experiment 1: The Same or Not The Same?

Experiment 1: The Same or Not The Same? Experiment 1: The Same or Not The Same? Learning Goals After you finish this lab, you will be able to: 1. Use Logger Pro to collect data and calculate statistics (mean and standard deviation). 2. Explain

More information

POE FINAL SEMESTER 2

POE FINAL SEMESTER 2 POE FINAL SEMESTER 2 MULTIPLE CHOICE 1. What is the purpose of the RobotC Debug window? a. It allows the user to Start and Stop their program. b. It allows the user to step through their program one line

More information

Lab 6d: Self-Erecting Inverted Pendulum (SEIP)

Lab 6d: Self-Erecting Inverted Pendulum (SEIP) Lab 6d: Self-Erecting Inverted Pendulum (SEIP) Arthur Schopen- Life swings like a pendulum backward and forward between pain and boredom. hauer 1 Objectives The goal of this project is to design a controller

More information