BALL ON PLATE BALANCING SYSTEM Progress Report for ECSE-4962 Control Systems Design

Size: px
Start display at page:

Download "BALL ON PLATE BALANCING SYSTEM Progress Report for ECSE-4962 Control Systems Design"

Transcription

1 BALL ON PLATE BALANCING SYSTEM Progress Report for ECSE-4962 Control Systems Design Greg Andrews Chris Colasuonno Aaron Herrmann March 24, 2004 Rensselaer Polytechnic Institute

2 Abstract The goal of the ball-on-plate balancing system is to create a control system that can accurately balance a steel ball on a plate. To date, significant strides have been made towards the completion of said goal. The physical system, including a rebuilt yoke, axle and motor bracket, is nearly complete. The basic controller has been coded, and is currently capable of gravity compensation, friction compensation, and following a sine wave input. The ball coordinate system is also complete, and can generate plate coordinates for use in the controller. With regard to the originally proposed schedule, tasks are continuing to be completed ahead of schedule.

3 Contents 1 Introduction 4 2 Preliminary Results Model Development Control Development Friction Identification Friction & Gravity Cancellation Validation Subsystem Development Summary of Progress Plan Schedule Cost Unanticipated Challenges Forecast Statement of Contribution 27 A MATLAB Code 29 1

4 List of Figures 2.1 Simulink Diagram - Complete System State Feedback Control (LQR) - Step Response Simulink diagram for Observer Control State Feedback Control with Observer - Step Response Plate Frequency Response Ball Control - Root Locus Ball Control - Step Response Ball Control - Frequency Response Ball Position with Time - Circular Trajectory Absolute Ball Position in Meters Simulink Virtual Reality Diagram D Animation of The Ball on Plate System Pan Axis Friction Data Tilt Axis Friction Data Gravity Compensation Torque Data Open Loop Response for 2.1 N-m Torque, Actual and Simulated Step Response Tracking Error for 1.5 rad/sec sine wave Tracking Error for 3.0 rad/sec sine wave xpc Target Touchpad Interface xpc Target Touchpad Packet Conversion Touchpad Ball Test

5 List of Tables 2.1 Touchpad Controller Packet composition Remaining schedule List of parts List of raw materials Labor costs

6 Chapter 1 Introduction The goal of this project is to develop a ball-on-plate balancing system, capable of controlling the position of a ball on a plate for both static positions as well as smooth paths. We intend that the initially horizontal plate will be tilted along each of two horizontal axes in order to control the position of the ball. Each tilting axis will be operated on by an electric motor. Each motor will be controlled using software, with a minimum of position feedback for control. After an extensive search, few systems of similar scale were found. The ball-on-beam system, a 1-dimensional similarity to the ball-on-plate, however, is a classic control problem, and has been studied in great detail, and solved a great many ways; PID control, optimal control, fuzzy-logic controllers, etc. The fuzzy-logic controllers would seem to be the current state of the art, however classical approaches using discrete approximations are certainly adequate, if not preferred for their relative ease of implementation. Two ball-on-plate systems were uncovered during the search: one, developed at Rensselaer Polytechnic Institute by Professor Kevin Craig [6] using a similar method to that which we intend, and another at the University of Newcastle, Australia, which was developed using image processing techniques in conjunction with a textbook by Professors Graham Goodwin, Stefan Graebe and Mario Salgado [7]. While this would seem to be a short list, the ball and beam system seems to be a more popular and less structurally complex system to implement. The aim of this project will be to create a ball-plate system using a resistive touch sensor to allow the movement of a ball by means of automatic control. The system should have accuracy of < 2% in the placement of the ball on the screen, as well as the ability to move the ball from one end of the plate to the other in less than 2 seconds (long side). Overshoot should be minimal, to reduce the chances of losing the ball off of the plate or incurring damage to the touch element due to striking the physical structure of the system. Current progress to date has shown great strides towards the creation of a fully modelled, fully controlled balancing system. The modelling of the dynamics of the system have been completed, and the simulated model validated by means of comparison to the physical system. The friction of the system has also been identified through successive trials using varying torque inputs on both axes. A controller with full statefeedback and an observer has also been designed, and is currently undergoing testing and incremental tuning. The touchpad sensor interface is also complete, and waiting to be attached to the now completed mechanical system. 4

7 Comparing the progress with the proposed initial schedule, work is proceeding as planned. This week is the integration phase, and work is continuing on that front, with the physical system and sensors being married together. Then the controller can finally be tested on the complete system, aiming for ball balancing some time in the next week. The interface for the touchpad did have to be changed to using the serial controller that came with the touchpad itself, but it all functions as expected. There are concerns that the motor drivers cannot supply enough torque for our system with the current setup, and therefore might require tweaking. The prognosis for the remaining 5 weeks of development looks good. If the controller works as the simulation shows, the basic objective of balancing a ball seems plausible. Given all present indications, the further goal of tracing a path also seems possible. 5

8 Chapter 2 Preliminary Results 2.1 Model Development In order to design a control system that will accurately control the position of the ball, a highly accurate model must be developed. As the accuracy of the model increases, the control effort required will be less. To develop this model, Professor Wen s pantilt.m MATLAB script was run to find the equations of motion for our system. This script returns symbolic values for the mass-inertia matrix, velocity coupling matrix, gravity loading vector, and the total system energy. A SolidWorks model was developed, and from this, numeric inertia tensors were found for bodies A and B with respect to our defined coordinate systems. Unfortunately, using the linear control theory that we have learned thus far, it becomes difficult to develop a control system for our fully non-linear model. Because of this, the system must be linearized about an operating condition, ( θ, θ) = (0, θ d ). By doing this, we are left with the linearized equations of motion: The state-space realization of this system becomes [5]: [ ] x1 = x 2 M(θ d ) θ + G(θ d) (θ θ d ) + F v θ = Bu Fc sgn( θ θ) (2.1) M 1 (θ d ) G θ }{{} 2x2 y = M 1 F v }{{} 2x2 [ ] [ x1 x 2 ] ] + x 2 [ x1 Using this linearized system, a controller can be developed for the plate (2.2) 6

9 In addition to the plate system, a model for the ball dynamics must be developed as well. If we ignore coupling between the two modes of motion, as well as the friction between the ball and plate, a linear model and transfer function can be determined [3]. ( J r 2 b + m b )ẍ = m b gθ X(s) Θ(s) = mg s 2 ( J + m) r 2 b (2.3) Substituting numerical values into this equation results in the transfer function 7 s 2. This double integrator can be easily controlled with classical control approaches. 2.2 Control Development The design approach for this control consists of two feedback loops: an inner loop to control the position of the plate, and an outer loop to control the position of the ball [6]. A Simulink diagram illustrating this approach can be seen in Figure 2.1. Figure 2.1: Simulink Diagram - Complete System In order to successfully implement this design, the inner loop must have a much faster response than the outer loop. Since the inner loop can only be designed to be as fast as physical limitations allow (motor torque, etc.), we must intentionally design the outer loop to be slower. From the linearized system in Equation 2.2, a full state-feedback control can be implemented. For our system we decided to use a linear quadratic regulator (LQR) to determine the feedback gain matrix, K, such that the control becomes u = Kx. The Q matrix must be chosen to optimize the control to achieve 7

10 out desired result. Since we are interested in tracking θ 1 and θ 2, we place a high weighting on those states. In addition, the R function can be adjusted to either promote or penalize the control effort. After several design iterations, the current Q and R matrices are found to be: Q = R = [ ] (2.4) resulting in the feedback gain matrix: [ ] K = (2.5) With this gain matrix, the closed loop eigenvalues (A BK) are placed so that the damping ratio is ζ =.707 and natural frequency is ω n = 6.68 rad/sec. The step response of this closed-loop system can be seen in Figure 2.2. However, this response assumes that all states can be measured, when in fact we can only Figure 2.2: State Feedback Control (LQR) - Step Response measure position, not velocity. For this reason, we have implemented an observer to estimate the velocity states of our system [4]. To do this, the plant was first converted to a discrete system using MATLAB s c2d() command using the zero-order hold method for a sampling frequency of 10KHz. Then, observer poles are placed so that they are roughly five times faster than the closed-loop poles. To do this, we find the time constant of the closed-loop poles, and calculate our observer poles accordingly. Using MATLAB s place() command, the observer gain matrix L is found to place the poles in these desired locations. The observer is of the form: ˆx = Aˆx(k) + Bu(k) + L(y(k) ŷ(k)) (2.6) 8

11 ŷ(k) = Cˆx(k) P oles = 1e 3 [ j j j j] (2.7) 2 0 L = (2.8) where ˆx is the observer s estimate of the velocity states, u is the system input, y is the plant output, and ŷ is the observer output. The L matrix ensures that the observer error, ˆx(k) x(k) converges to zero [2]. This can easily be implemented as a controller of the form [8]: u(k) = Kˆx(k) ˆx(k + 1) = (A BK LC)ˆx(k) + Ly(k) (2.9) The Simulink diagram and response for this system can be seen in Figures 2.3 and 2.4. The observer Figure 2.3: Simulink diagram for Observer Control estimates the velocity fairly accurately, however this may be able to improve my moving the eigenvalues of the observer (2.7). The closed-loop frequency response as well as gain and phase margins for this system can be seen in Figure 2.5. It can be seen from this response that we should be able to track the plate at a velocity of 6.7 rad/sec, while at the same time suppressing high-frequency sensor noise. This meets our original specification of 1.36 rad/sec. The gain margin for the closed-loop plate system is 80.6dB at 138 rad/sec. At our desired speed, we should be able to position the plate with very little chance of instability. It should be noted that in Figure 2.1, that the gravity and friction terms are being added back into the control effort. This feedback linearization in effect cancels out the nonlinear terms within the plant, making the control effort required less. However, this does not come without cost. The feedback linearization increases computation time, as well as the torque requirement, though through both simulation and actual experimental runs, this does not seem to pose a problem. For the ball position control, a classical root-locus design methodology was used. Figure 2.6 shows the locus before and after compensation. It can be seen from the prior that the open-loop system is only marginally stable, and a purely proportional controller will not be sufficient to compensate for this. Instead a proportional+integral+derivative (PID) control will be used. A zero is placed at s = 1 2, and a pole to the far right at s = 100 resulting in a derivative gain of K d = 2. By using MATLAB s rltool(), a proportional gain of K p =1 was found. In addition, a small integral term was added to improve the steady state response. 9

12 Figure 2.4: State Feedback Control with Observer - Step Response Figure 2.5: Plate Frequency Response 10

13 Figure 2.6: Ball Control - Root Locus An integral gain of Kp = 1.05 was used to achieve this. closed-loop response can be seen in Figure 2.7. With these relatively low gains, our control is sufficiently slow to allow the plate dynamics to respond. 14s s s 4 + s s s (2.10) Equation 2.10 shows the closed-loop transfer function for the ball dynamics. The controller K p + K d s + frack i s can be converted to a digital controller using MATLAB s c2d() command. This emulation design approach can be used since the sampling time is sufficiently faster than the bandwidth of the closed-loop system. After the discretization at a rate of 10KHz with a bilinear transform, the digital PID control becomes: 199z 2 398z z (2.11) The frequency response and gain and phase margins can be seen in Figure 2.8. It can be seen that with this control, we should be able to track the ball at 12 rad/sec, and high-frequency noise should be suppressed. This meets our original design requirements. Now that controllers have been developed separately for both plate position and ball position, it is desirable to to combine the two, resulting in the diagram shown in Figure 2.1. By doing this, the plate control is commanded by the output of the ball control. A simple test is to command a trajectory for the ball, and see if the plate dynamics respond in such a way to follow that trajectory. For this test, we used two sine waves, both at 2 rad/sec and amplitude of 0.04, and one inverted and π 2 radians out of phase with the other. One sine wave commanded the ball s X position, the other, the ball s Y position. By doing this, the ball should essentially travel in a circle of radius 0.04m. This trajectory was commanded though a Simulink simulation, and the results were promising. Figure 2.9 shows the ball s response in a position vs. time manner. It can 11

14 Figure 2.7: Ball Control - Step Response Figure 2.8: Ball Control - Frequency Response 12

15 Figure 2.9: Ball Position with Time - Circular Trajectory be seen that initially, the ball has a 0.04m position error since it s initial position is at (0,0). This does not cause the system to go unstable, however there is some lag and overshoot while the ball tries to catch up to the commanded position. Once the ball has caught up to the desired position, it tracks it with very little error. Figure 2.10 shows the balls spatial position in an X vs. Y position plot. The ball initially overshoots the desired trajectory as mentioned before, but then settles into a near perfect circular trajectory in roughly 3 seconds. To better visualize this, a 3D animation has been created using MATLAB s Virtual Reality Toolbox. The model created in SolidWorks was exported as a VRML file, and a VR block was created in Simulink to move the model in accordance with the simulation results. The Simulink block diagram and a sample frame from the animation are shown in Figures 2.11 and A video file of this animation is available upon request. 2.3 Friction Identification Identification of the friction in the system was performed as prescribed in the design proposal. A Simulink model capable of measuring the encoder and outputting constant voltages was used in conjunction with a MATLAB script to repeatedly estimate the velocity of each joint. For each of 200 voltage increments from minus two volts to plus to volts, the motor was allowed to turn for ten seconds so that it would reach steady state velocity. The last four seconds were then averaged to obtain a single value for steady state velocity for that particular torque (voltage). In addition, a one second ten volt spike was added in the beginning of each run in order to overcome the stiction of the system. By plotting this data and finding a least squares approximation for the data, the coulomb and viscous friction were found as the intercept and slope of the regression line, respectively. The plots for each axis are shown in Figures 2.13 and

16 Figure 2.10: Absolute Ball Position in Meters Figure 2.11: Simulink Virtual Reality Diagram 14

17 Figure 2.12: 3D Animation of The Ball on Plate System 15

18 Figure 2.13: Pan Axis Friction Data Figure 2.14: Tilt Axis Friction Data 16

19 2.4 Friction & Gravity Cancellation Following the identification of the friction and gravity, a Simulink diagram was created to cancel out both within the system. When the program was run, the system could be positioned by hand at any position without falling and was very easy to move. A fairly light touch could rotate the system about an axis several times before it settled at a location and remained there. Through some simple hand calculations, the amount of torque required to cancel gravity in the system was found to be about 0.4 N-m. This value matched the torque value in both the model and the value recorded from running gravity cancellation on the actual system. The torque plot can be seen in Figure Figure 2.15: Gravity Compensation Torque Data 2.5 Validation Having completed the identification of the system s inertia from the SolidWorks model, friction, and gravity loading, the model of the system was completed. In order to verify the validity of this model, several experiments were run on the system. These experiments included testing of the open loop response, step response, and position tracking, for both the actual system and a simulation using the developed model. The results were very promising. The open loop response for both the actual system and simulation for an input of a 2.1 N-m torque are shown in Figure The plots for both are nearly identical. With a preliminary control system running, the system s pan axis was commanded to a 0.5 radian position using a step function input. The actual, desired, and simulated responses are shown in Figure While 17

20 Figure 2.16: Open Loop Response for 2.1 N-m Torque, Actual and Simulated there is some variation between the actual and simulated responses including rise time and error, they are a fairly close match as well. In addition to a step response, several sine wave inputs were made to the controlled system and several promising plots were generated. Sine waves with amplitude of one radian and for 1.5 rad/s and 3.0 rad/sec frequency were used as input. Upon viewing the plots it is easy to see that while some further work is required on the controller, the model is highly accurate when compared to the actual system. Some slight bumping occurs on the downward stroke on one portion of the sine wave. By doing such things as increasing the speed of the observer by moving its poles, this bumping effect can be removed. The plots are shown in Figures 2.18 and A simple tolerance analysis test to verify the gain and phase margins (qualitatively) is to give the system a disturbance while in operation. While the system was being commanded to follow a sine wave input, we held the yoke from moving by hand. After letting go, the system sped up to catch up with the desired trajectory, and then fell back into sync. No tolerance analysis has yet been done as far as sensor noise, however according to the frequency responses of both controllers, high-frequency noise should be sufficiently attenuated. 2.6 Subsystem Development The touchpad interface relies entirely on the capabilities of the 3M Dynapro SC3 serial interface controller for its operation. The touchpad is composed of 90 offset plates. Voltage is applied across one plate while reading voltage information from the other plane. When pressure is applied to the surface, an electrical 18

21 Figure 2.17: Step Response Figure 2.18: Tracking Error for 1.5 rad/sec sine wave 19

22 Figure 2.19: Tracking Error for 3.0 rad/sec sine wave connection is made, which results in a change of voltage at the output. This change corresponds to the distance between the contacts on the plate. One reading is made from each of the two plates to create an X-Y coordinate pair. The SC3 controller takes these X-Y coordinate pairs it generates and converts them into sets of three 8-bit packets which can be converted into coordinate pairs. The actual coordinate values are 10-bit values, that are actually spread across the three separate packets as shown in Table 2.1. Note that in the table, the P bit refers to the status of the pen, or the object touching the pad: 1 is pen down, 0 is pen up. Also note that x9 refers to the 10th bit of the 10-bit x coordinate number, and so forth for all x k and y k. [1] Table 2.1: Touchpad Controller Packet composition Packet/Bit # #1 (sync) 1 P x 9 x 8 x 7 y 9 y 8 y 7 #2 (data) 0 x 6 x 5 x 4 x 3 x 2 x 1 x 0 #3 (data) 0 y 6 y 5 y 4 y 3 y 2 y 1 y 0 All of these packets are sent asynchronously and without prompting: as soon as the touchpad receives sufficient pressure for the controller to register a touch, the system begins to send data. In order to process this data, and get the resultant coordinate information into the real-time computer, a serial interface needs to be created in MATLAB Simulink that can be compiled for the xpc Target system. The basic overall system utilizes the binary receive block in Simulink to retrieve data as sets of three 1-byte packets as described in the manual. The RS232 Setup block sets the link parameters as 2400 bps, and 8-N-1-8 bits per packet, no parity, and 1 stop bit. Normally, Simulink is unable to utilize binary numbers, however, 20

23 the communications toolbox allows conversion to and from binary. This makes possible the individual bit manipulation necessary to move the 8-bit packets from the controller into the 10-bit binary words that the controller s A/D converter creates. The Simulink diagrams can be seen in figures 2.20 and Figure 2.20: xpc Target Touchpad Interface Figure 2.21: xpc Target Touchpad Packet Conversion Testing of the system in real time using the steel ball as a touch source as well as the rubber membrane on the surface of the touch screen yields clear coordinate plots such as the one seen in Figure Further testing will have to wait until the physical system is completed, including approximated error calculations due to quantization and signal noise. 21

24 Figure 2.22: Touchpad Ball Test 22

25 Chapter 3 Summary of Progress 3.1 Plan The basic project plan remains unchanged: upon completion, the system should autonomously balance a ball on a plate. To that end, the system has been modelled and linearized, and a controller designed around the dynamics of the ball and the two-axis pan-tilt mechanism. Plans also remain in place to allow the system to put the ball into different planned paths, including for example a circle or a figure-eight shape. Further development could also involve a graphical user interface. 3.2 Schedule To date, progress has been as scheduled with only minor glitches or setbacks during the construction and development. Of note is the construction of the physical system in the RPI Student Machine Shop, which took significantly longer than originally thought. The end result is acceptable for our system, though it remains to be tested as a complete system. Other steps, however, proceeded as planned: model development, friction id, validation and control system development all on schedule, as evidenced by the results detailed previously in this report. The remainder of the schedule remains as originally planned, shown in Table 3.1. This week is devoted to sensor integration and control system testing and development. The real work now is focused on the completion of the physical system with sensors, and the testing of the simulated control system against a fully working real system. If things proceed as desired, ball balancing should occur within the next week or two, proceeding thus to planned ball trajectories. 23

26 Table 3.1: Remaining schedule Week Task Member Week 10 Integration of sensors Aaron Control system testing Greg Sensor testing Chris Week 11 Static ball balancing Team Week 12 Complex path following Team Week 13 Work on final report Team Final demonstration Team Week 14 Work on final report Team Final presentation Team Week 15 Final report Team 3.3 Cost Costs have remained as originally planned, mostly due to a large allowance for aluminum usage during construction of the yoke and axis. This previously conceived overestimate turned out to be quite accurate, due to errors made during machining. In fact, several pieces of the yoke and axle had to be completely remade due to errors. One item of mention not previously introduced in the project proposal is a Lexan panel. The touch pad sensor is constructed with a glass substrate, and while stiff, glass is not shatterproof. It was the consensus of the team members that during testing, a Lexan panel stand in as the sensor plate, so that the expensive and difficult to source touch sensor was not damaged. This plate will also serve as protection for the touch sensor during operation, and perhaps as a stiffener, providing structural support to the sensor. A new tilt axis belt was also purchased because of the changes made to the dimensions of the yoke. Due to the uncertainty of the outcome of the machining process, the belt purchase was put off until recently, to be certain of choosing the correct size. The new belt ties directly into the new tilt drive system, made possible by using a remanufactured tilt motor bracket from last year s project. This also saved significant machining time. 3.4 Unanticipated Challenges Several unanticipated challenges have come up during system development. Of particular concern involves the required torque for normal system operation. During testing, it was realized that the magnitude of torque required by the system was larger than expected, approaching or exceeding the saturation point of the motor drivers. Further testing is planned to ascertain if the system is feasible with the drivers configured as they are currently, or if the D/A+Motor driver system might have to be tweaked to generate more amperage. A further controller-related challenge is related to the observer design. Several initial implementations failed to work as well as the basic finite difference. This is obviously a problem related to the placement of the poles or the implementation in Simulink, and should be corrected upon further discussion on the topic with Professor John Wen. 24

27 Table 3.2: List of parts Item Qty Cost Total Source 1 1/4 diam. 440C stainless ball 1 $9.17 $9.17 McMaster-Carr Dynapro wire resistive touch pad 1 $39 $39 Ebay Pittman motor GM9234S017 (pan) 1 $97.59 $97.59 Supplied Pittman motor GM9234S017 (tilt) 1 $97.59 $97.59 Supplied Pan gear A 1 $9.97 $9.97 Supplied Pan gear B 1 $22.02 $22.02 Supplied Tilt gear A 1 $7.95 $7.95 Supplied Tilt gear B 1 $22.02 $22.02 Supplied Pan belt 1 $3.92 $3.92 Supplied Tilt belt 1 $3.55 $ Misc screws $5.00 $5.00 Home Depot Total $ Table 3.3: List of raw materials Item Qty Cost Total Source 1/2 aluminum stock 5 lb $4/lb $20 RPI Machine Shop 1/16 latex rubber membrane 1 $ x12 $9.38 McMaster-Carr.093 Lexan panel 1 $ x10 $5.00 Home Depot Total $34.38 Table 3.4: Labor costs Description Hours Cost Total Andrews, Greg (engineer) 300 $35/hr $10,500 Colasuonno, Chris (engineer) 300 $35/hr $10,500 Herrmann, Aaron (engineer) 300 $35/hr $10,500 Caskey, Ryan (machinist) 30 $35/hr $1,050 Total 930 $32,550 25

28 An unanticipated challenge presented itself during the machining of the yoke and axle. Despite a strict attention to detail for all of the dimensions of the parts, a simple detail was misunderstood with regard to the axle bearings. Upon discussion with TA Benjamin Potsaid, it became apparent that the holes for the axle bearings needed to be slightly smaller than needed, so as to press fit the bearings. However, the holes made are in fact exactly to size, yielding a loose fit. This isn t expected to impact the performance of the system simply because the system is not meant to spin, merely to rotate back and forth through small angular displacements. In the area of subsystem development, the expectation was that A/D conversion for the generation of touch pad coordinates would be done by the analog inputs of the xpc Target computer. However, comprehending the outputs from the touch pad itself proved difficult at best. Since the controller included with the purchased touch pad worked, an xpc Target based serial port interface system was created to interface with the controller and generate ball coordinates for the control system. Another challenge related to the touchpad is the configuration of the serial controller. Several attempts have been made to change the averaging, settling time and baud rate settings of the controller with zero success. Though the timing and format of the messages are known, the controller seems to ignore the settings. It is not yet known whether this is merely an error in the controller, or merely a failure to understand the message formats. However, successfully configuring the controller could yield a significant improvement in the sampling period of the ball coordinate generation system. A challenge that has recently come to light is the zeroing of the axes upon system startup. Simplicity dictates that development forego the usage of inclinometers, simply to make the work easier. However, it has proven difficult to get the axes initially perfectly zeroed for just a test of the pan axis. Once the system is physically completed and testing of the balancing system commence, finding a zero point could prove to be difficult. And if that measurement isn t correct, the error trickles through all of the systems: gravity compensation is wrong, encoder angles are wrong. Ultimately, the answer might very well be to create a jig for the inclinometers that allows a quick startup configuration and then the subsequent removal of the jig during a test. 3.5 Forecast A reasonable forecast for the remainder of the project suggests that at the very least, we will complete the balancing problem. Whether or not the system can be made to overcome the present challenges and track out a ball path is still unknown, though the group is willing to put in the time to make certain it can. All that remains to be seen is what the controller is capable of, and what it can be made to do with proper testing and tuning. 26

29 Chapter 4 Statement of Contribution For the progress report document: Greg completed the following sections: Model development Controller development Chris completed the following sections: Validation Friction Identification Friction & Gravity Cancellation Aaron completed the following sections: Abstract Introduction Subsystem Development Summary of Progress Greg Andrews Chris Colasuonno Aaron Herrmann x x x 27

30 Bibliography [1] 3M Touch Systems. SC3 Touch Screen Controller: User s Guide, 2nd edition, [2] Dr. Murat Arcak. Discrete time systems - lecture notes [3] No Author Available. Control tutorials for matlab: Modeling the ball and beam experiment. Available WWW: jzelek/matlab/ctms/examples/ball/ball.htm. [4] No Author Available. Control tutorials for matlab: State space tutorial. Available WWW: http: // [5] No Author Available. Digital control example: Inverted pendulum using state space method. Available WWW: jzelek/matlab/ctms/examples/pend/diginvss.htm. [6] S. Awtar, C. Bernard, N. Boklund, A. Master, D. Ueda, and K. Craig. Mechatronic design of a ball-onplate balancing system. Technical report, Rensselaer Polytechnic Institute, [7] Graham Goodwin, Stefan Graebe, and Mario Salgado. Control system design - ball-on-plate tutorial. Available WWW: sim.html, [8] C. Phillips and H. Nagle. Digital control system analysis and design, third edition. Technical report, Prentice Hall, Inc.,

31 Appendix A MATLAB Code % Greg Andrews % System Linearization and Control System setup % March 15, 2004 % Control System Design %Symbolic Variables syms ma mb g t1 t2 lca1 lca2 lca3 lcb1 lcb2 lcb3 Im1 Im2 N1 N2 syms IA11 IA12 IA13 IA21 IA22 IA23 IA31 IA32 IA33 syms IB11 IB12 IB13 IB21 IB22 IB23 IB31 IB32 IB33 %Gravity Vector G1= -ma*g*sin(t1)*lca1-ma*g*cos(t1)*lca2-mb*g*sin(t1)*cos(t2)*lcb1-mb*g*cos(t1)*lcb2-mb*g*sin(t1)*sin(t2)*lc G2= -mb*g*cos(t1)*sin(t2)*lcb1+mb*g*cos(t1)*cos(t2)*lcb3; %Gradient of the Gravity Vector partial_g=[diff(g1, t1 ) diff(g1, t2 ); diff(g2, t1 ) diff(g2, t2 )]; %Mass-Inertia Matrix M11= IA33+mA*lcA1^2+mA*lcA2^2+Im1*N1^2+IB11-IB11*cos(t2)^2+mB*lcB2^2+mB*lcB3^2-mB*lcB3^2*cos(t2)^2-2*sin(t2)* M12= -sin(t2)*ib12+sin(t2)*mb*lcb1*lcb2+cos(t2)*ib23-cos(t2)*mb*lcb2*lcb3; M21= -sin(t2)*ib12+sin(t2)*mb*lcb1*lcb2+cos(t2)*ib23-cos(t2)*mb*lcb2*lcb3; M22= IB22+mB*lcB1^2+mB*lcB3^2+Im2*N2^2; 29

32 M=[M11 M12; M21 M22]; % % Numerical Parameters g=9.81; Im1=11.5; Im2=11.5; ma = ; % mass of link A in Kg lca1 =.0016; % distance to COM lca2 = ; lca3 = ; mb = ; lcb1 = ; lcb2 = ; lcb3 =.0003; N1=2*11.5; N2=4*11.5; % total gear ratio IA11 = ; % inertia IA12 = ; IA13 = ; IA21 = ; IA22 = ; IA23 = ; IA31 = ; IA32 = ; IA33 = ; IB11 = ; IB12 = 0; IB13 = ; IB21 = 0; IB22 = ; IB23 = 0; IB31 = ; IB32 = 0; IB33 = ; fc1 =.097; % friction fv1 =.0019; fv2 = ; fc2 = ; t1=0; t2=0; G_lin=vpa(subs(partial_G)); M_lin=vpa(subs(M)); Fv=[fv1 0; 0 fv2]; Astuff1=-inv(M_lin)*G_lin; Astuff2=-inv(M_lin)*Fv; % State space representation A=[ ; ; Astuff1(1,1) Astuff1(1,2) Astuff2(1,1) Astuff2(1,2); Astuff1(2,1) Astuff1(2,2) Astuff2(2,1) Astuff2(2,2)]; A=subs(A); B=[0 0; 0 0; 1 0; 0 1]; C=[ ; ]; D=[0 0; 0 0]; sys_c=ss(a,b,c,d); sys_d=c2d(sys_c,.0001); % LQR w1=1000; w2=1000; w3=1; w4=1; Q=[w ; 0 w2 0 0; 0 0 w3 0; w4]; R=.5*eye(2); 30

33 K=lqr(A,B,Q,R); % Observer PL=[ ]; L=place(A,C,PL) ; Aobs=(A-B*K-L*C); Bobs=L; Cobs=K; Dobs=D; Obs=ss(Aobs,Bobs,Cobs,Dobs); Ts=.0001; Obs=c2d(Obs,Ts); 31

Frequency Response Analysis and Design Tutorial

Frequency Response Analysis and Design Tutorial 1 of 13 1/11/2011 5:43 PM Frequency Response Analysis and Design Tutorial I. Bode plots [ Gain and phase margin Bandwidth frequency Closed loop response ] II. The Nyquist diagram [ Closed loop stability

More information

Optimal Control System Design

Optimal Control System Design Chapter 6 Optimal Control System Design 6.1 INTRODUCTION The active AFO consists of sensor unit, control system and an actuator. While designing the control system for an AFO, a trade-off between the transient

More information

Pan-Tilt Signature System

Pan-Tilt Signature System Pan-Tilt Signature System Pan-Tilt Signature System Rob Gillette Matt Cieloszyk Luke Bowen Final Presentation Introduction Problem Statement: We proposed to build a device that would mimic human script

More information

GE420 Laboratory Assignment 8 Positioning Control of a Motor Using PD, PID, and Hybrid Control

GE420 Laboratory Assignment 8 Positioning Control of a Motor Using PD, PID, and Hybrid Control GE420 Laboratory Assignment 8 Positioning Control of a Motor Using PD, PID, and Hybrid Control Goals for this Lab Assignment: 1. Design a PD discrete control algorithm to allow the closed-loop combination

More information

Servo Tuning. Dr. Rohan Munasinghe Department. of Electronic and Telecommunication Engineering University of Moratuwa. Thanks to Dr.

Servo Tuning. Dr. Rohan Munasinghe Department. of Electronic and Telecommunication Engineering University of Moratuwa. Thanks to Dr. Servo Tuning Dr. Rohan Munasinghe Department. of Electronic and Telecommunication Engineering University of Moratuwa Thanks to Dr. Jacob Tal Overview Closed Loop Motion Control System Brain Brain Muscle

More information

Penn State Erie, The Behrend College School of Engineering

Penn State Erie, The Behrend College School of Engineering Penn State Erie, The Behrend College School of Engineering EE BD 327 Signals and Control Lab Spring 2008 Lab 9 Ball and Beam Balancing Problem April 10, 17, 24, 2008 Due: May 1, 2008 Number of Lab Periods:

More information

The Air Bearing Throughput Edge By Kevin McCarthy, Chief Technology Officer

The Air Bearing Throughput Edge By Kevin McCarthy, Chief Technology Officer 159 Swanson Rd. Boxborough, MA 01719 Phone +1.508.475.3400 dovermotion.com The Air Bearing Throughput Edge By Kevin McCarthy, Chief Technology Officer In addition to the numerous advantages described in

More information

JUNE 2014 Solved Question Paper

JUNE 2014 Solved Question Paper JUNE 2014 Solved Question Paper 1 a: Explain with examples open loop and closed loop control systems. List merits and demerits of both. Jun. 2014, 10 Marks Open & Closed Loop System - Advantages & Disadvantages

More information

SRV02-Series Rotary Experiment # 3. Ball & Beam. Student Handout

SRV02-Series Rotary Experiment # 3. Ball & Beam. Student Handout SRV02-Series Rotary Experiment # 3 Ball & Beam Student Handout SRV02-Series Rotary Experiment # 3 Ball & Beam Student Handout 1. Objectives The objective in this experiment is to design a controller for

More information

Position Control of DC Motor by Compensating Strategies

Position Control of DC Motor by Compensating Strategies Position Control of DC Motor by Compensating Strategies S Prem Kumar 1 J V Pavan Chand 1 B Pangedaiah 1 1. Assistant professor of Laki Reddy Balireddy College Of Engineering, Mylavaram Abstract - As the

More information

EE 560 Electric Machines and Drives. Autumn 2014 Final Project. Contents

EE 560 Electric Machines and Drives. Autumn 2014 Final Project. Contents EE 560 Electric Machines and Drives. Autumn 2014 Final Project Page 1 of 53 Prof. N. Nagel December 8, 2014 Brian Howard Contents Introduction 2 Induction Motor Simulation 3 Current Regulated Induction

More information

Fundamentals of Servo Motion Control

Fundamentals of Servo Motion Control Fundamentals of Servo Motion Control The fundamental concepts of servo motion control have not changed significantly in the last 50 years. The basic reasons for using servo systems in contrast to open

More information

Control Design for Servomechanisms July 2005, Glasgow Detailed Training Course Agenda

Control Design for Servomechanisms July 2005, Glasgow Detailed Training Course Agenda Control Design for Servomechanisms 12 14 July 2005, Glasgow Detailed Training Course Agenda DAY 1 INTRODUCTION TO SYSTEMS AND MODELLING 9.00 Introduction The Need For Control - What Is Control? - Feedback

More information

Advanced Servo Tuning

Advanced Servo Tuning Advanced Servo Tuning Dr. Rohan Munasinghe Department of Electronic and Telecommunication Engineering University of Moratuwa Servo System Elements position encoder Motion controller (software) Desired

More information

Root Locus Design. by Martin Hagan revised by Trevor Eckert 1 OBJECTIVE

Root Locus Design. by Martin Hagan revised by Trevor Eckert 1 OBJECTIVE TAKE HOME LABS OKLAHOMA STATE UNIVERSITY Root Locus Design by Martin Hagan revised by Trevor Eckert 1 OBJECTIVE The objective of this experiment is to design a feedback control system for a motor positioning

More information

Ball Balancing on a Beam

Ball Balancing on a Beam 1 Ball Balancing on a Beam Muhammad Hasan Jafry, Haseeb Tariq, Abubakr Muhammad Department of Electrical Engineering, LUMS School of Science and Engineering, Pakistan Email: {14100105,14100040}@lums.edu.pk,

More information

Automatic Control Motion control Advanced control techniques

Automatic Control Motion control Advanced control techniques Automatic Control Motion control Advanced control techniques (luca.bascetta@polimi.it) Politecnico di Milano Dipartimento di Elettronica, Informazione e Bioingegneria Motivations (I) 2 Besides the classical

More information

SOUND TRACKING PAN-TILT MACHINE. Progress Report for ECSE-4962 Control Systems Design

SOUND TRACKING PAN-TILT MACHINE. Progress Report for ECSE-4962 Control Systems Design SOUND TRACKING PAN-TILT MACHINE Progress Report for ECSE-4962 Control Systems Design Kevin Murphy Matthew Daigle Matthew Gates Vadiraj Hombal March 24 th, 24 Rensselaer Polytechnic Institute ii Executive

More information

Application Note #2442

Application Note #2442 Application Note #2442 Tuning with PL and PID Most closed-loop servo systems are able to achieve satisfactory tuning with the basic Proportional, Integral, and Derivative (PID) tuning parameters. However,

More information

Motor Modeling and Position Control Lab 3 MAE 334

Motor Modeling and Position Control Lab 3 MAE 334 Motor ing and Position Control Lab 3 MAE 334 Evan Coleman April, 23 Spring 23 Section L9 Executive Summary The purpose of this experiment was to observe and analyze the open loop response of a DC servo

More information

Rectilinear System. Introduction. Hardware

Rectilinear System. Introduction. Hardware Rectilinear System Introduction This lab studies the dynamic behavior of a system of translational mass, spring and damper components. The system properties will be determined first making use of basic

More information

Robot Joint Angle Control Based on Self Resonance Cancellation Using Double Encoders

Robot Joint Angle Control Based on Self Resonance Cancellation Using Double Encoders Robot Joint Angle Control Based on Self Resonance Cancellation Using Double Encoders Akiyuki Hasegawa, Hiroshi Fujimoto and Taro Takahashi 2 Abstract Research on the control using a load-side encoder for

More information

Magnetic Levitation System

Magnetic Levitation System Magnetic Levitation System Electromagnet Infrared LED Phototransistor Levitated Ball Magnetic Levitation System K. Craig 1 Magnetic Levitation System Electromagnet Emitter Infrared LED i Detector Phototransistor

More information

Active Vibration Isolation of an Unbalanced Machine Tool Spindle

Active Vibration Isolation of an Unbalanced Machine Tool Spindle Active Vibration Isolation of an Unbalanced Machine Tool Spindle David. J. Hopkins, Paul Geraghty Lawrence Livermore National Laboratory 7000 East Ave, MS/L-792, Livermore, CA. 94550 Abstract Proper configurations

More information

Implementation of Proportional and Derivative Controller in a Ball and Beam System

Implementation of Proportional and Derivative Controller in a Ball and Beam System Implementation of Proportional and Derivative Controller in a Ball and Beam System Alexander F. Paggi and Tooran Emami United States Coast Guard Academy Abstract This paper presents a design of two cascade

More information

MTE 360 Automatic Control Systems University of Waterloo, Department of Mechanical & Mechatronics Engineering

MTE 360 Automatic Control Systems University of Waterloo, Department of Mechanical & Mechatronics Engineering MTE 36 Automatic Control Systems University of Waterloo, Department of Mechanical & Mechatronics Engineering Laboratory #1: Introduction to Control Engineering In this laboratory, you will become familiar

More information

Embedded Control Project -Iterative learning control for

Embedded Control Project -Iterative learning control for Embedded Control Project -Iterative learning control for Author : Axel Andersson Hariprasad Govindharajan Shahrzad Khodayari Project Guide : Alexander Medvedev Program : Embedded Systems and Engineering

More information

UNIT 2: DC MOTOR POSITION CONTROL

UNIT 2: DC MOTOR POSITION CONTROL UNIT 2: DC MOTOR POSITION CONTROL 2.1 INTRODUCTION This experiment aims to show the mathematical model of a DC motor and how to determine the physical parameters of a DC motor model. Once the model is

More information

Hydraulic Actuator Control Using an Multi-Purpose Electronic Interface Card

Hydraulic Actuator Control Using an Multi-Purpose Electronic Interface Card Hydraulic Actuator Control Using an Multi-Purpose Electronic Interface Card N. KORONEOS, G. DIKEAKOS, D. PAPACHRISTOS Department of Automation Technological Educational Institution of Halkida Psaxna 34400,

More information

A Do-and-See Approach for Learning Mechatronics Concepts

A Do-and-See Approach for Learning Mechatronics Concepts Proceedings of the 5 th International Conference of Control, Dynamic Systems, and Robotics (CDSR'18) Niagara Falls, Canada June 7 9, 2018 Paper No. 124 DOI: 10.11159/cdsr18.124 A Do-and-See Approach for

More information

dspace DS1103 Control Workstation Tutorial and DC Motor Speed Control Project Report

dspace DS1103 Control Workstation Tutorial and DC Motor Speed Control Project Report dspace DS1103 Control Workstation Tutorial and DC Motor Speed Control Project Report By Annemarie Thomas Advisor: Dr. Winfred Anakwa May 12, 2009 Abstract The dspace DS1103 software and hardware tools

More information

Motomatic Servo Control

Motomatic Servo Control Exercise 2 Motomatic Servo Control This exercise will take two weeks. You will work in teams of two. 2.0 Prelab Read through this exercise in the lab manual. Using Appendix B as a reference, create a block

More information

-binary sensors and actuators (such as an on/off controller) are generally more reliable and less expensive

-binary sensors and actuators (such as an on/off controller) are generally more reliable and less expensive Process controls are necessary for designing safe and productive plants. A variety of process controls are used to manipulate processes, however the most simple and often most effective is the PID controller.

More information

MEM01: DC-Motor Servomechanism

MEM01: DC-Motor Servomechanism MEM01: DC-Motor Servomechanism Interdisciplinary Automatic Controls Laboratory - ME/ECE/CHE 389 February 5, 2016 Contents 1 Introduction and Goals 1 2 Description 2 3 Modeling 2 4 Lab Objective 5 5 Model

More information

SELF-BALANCING MOBILE ROBOT TILTER

SELF-BALANCING MOBILE ROBOT TILTER Tomislav Tomašić Andrea Demetlika Prof. dr. sc. Mladen Crneković ISSN xxx-xxxx SELF-BALANCING MOBILE ROBOT TILTER Summary UDC 007.52, 62-523.8 In this project a remote controlled self-balancing mobile

More information

CHASSIS DYNAMOMETER TORQUE CONTROL SYSTEM DESIGN BY DIRECT INVERSE COMPENSATION. C.Matthews, P.Dickinson, A.T.Shenton

CHASSIS DYNAMOMETER TORQUE CONTROL SYSTEM DESIGN BY DIRECT INVERSE COMPENSATION. C.Matthews, P.Dickinson, A.T.Shenton CHASSIS DYNAMOMETER TORQUE CONTROL SYSTEM DESIGN BY DIRECT INVERSE COMPENSATION C.Matthews, P.Dickinson, A.T.Shenton Department of Engineering, The University of Liverpool, Liverpool L69 3GH, UK Abstract:

More information

Design of a Simulink-Based Control Workstation for Mobile Wheeled Vehicles with Variable-Velocity Differential Motor Drives

Design of a Simulink-Based Control Workstation for Mobile Wheeled Vehicles with Variable-Velocity Differential Motor Drives Design of a Simulink-Based Control Workstation for Mobile Wheeled Vehicles with Variable-Velocity Differential Motor Drives Kevin Block, Timothy De Pasion, Benjamin Roos, Alexander Schmidt Gary Dempsey

More information

Rotary Motion Servo Plant: SRV02. Rotary Experiment #02: Position Control. SRV02 Position Control using QuaRC. Student Manual

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

More information

Rotary Motion Servo Plant: SRV02. Rotary Experiment #03: Speed Control. SRV02 Speed Control using QuaRC. Student Manual

Rotary Motion Servo Plant: SRV02. Rotary Experiment #03: Speed Control. SRV02 Speed Control using QuaRC. Student Manual Rotary Motion Servo Plant: SRV02 Rotary Experiment #03: Speed Control SRV02 Speed Control using QuaRC Student Manual Table of Contents 1. INTRODUCTION...1 2. PREREQUISITES...1 3. OVERVIEW OF FILES...2

More information

SERVOSTAR Position Feedback Resolution and Noise

SERVOSTAR Position Feedback Resolution and Noise APPLICATION NOTE ASU010H Issue 1 SERVOSTAR Position Resolution and Noise Position feedback resolution has two effects on servo system applications. The first effect deals with the positioning accuracy

More information

ME 5281 Fall Homework 8 Due: Wed. Nov. 4th; start of class.

ME 5281 Fall Homework 8 Due: Wed. Nov. 4th; start of class. ME 5281 Fall 215 Homework 8 Due: Wed. Nov. 4th; start of class. Reading: Chapter 1 Part A: Warm Up Problems w/ Solutions (graded 4%): A.1 Non-Minimum Phase Consider the following variations of a system:

More information

Andrea Zanchettin Automatic Control 1 AUTOMATIC CONTROL. Andrea M. Zanchettin, PhD Spring Semester, Linear control systems design

Andrea Zanchettin Automatic Control 1 AUTOMATIC CONTROL. Andrea M. Zanchettin, PhD Spring Semester, Linear control systems design Andrea Zanchettin Automatic Control 1 AUTOMATIC CONTROL Andrea M. Zanchettin, PhD Spring Semester, 2018 Linear control systems design Andrea Zanchettin Automatic Control 2 The control problem Let s introduce

More information

Lecture 2 Exercise 1a. Lecture 2 Exercise 1b

Lecture 2 Exercise 1a. Lecture 2 Exercise 1b Lecture 2 Exercise 1a 1 Design a converter that converts a speed of 60 miles per hour to kilometers per hour. Make the following format changes to your blocks: All text should be displayed in bold. Constant

More information

Position Control of AC Servomotor Using Internal Model Control Strategy

Position Control of AC Servomotor Using Internal Model Control Strategy Position Control of AC Servomotor Using Internal Model Control Strategy Ahmed S. Abd El-hamid and Ahmed H. Eissa Corresponding Author email: Ahmednrc64@gmail.com Abstract: This paper focuses on the design

More information

CHAPTER 6 INTRODUCTION TO SYSTEM IDENTIFICATION

CHAPTER 6 INTRODUCTION TO SYSTEM IDENTIFICATION CHAPTER 6 INTRODUCTION TO SYSTEM IDENTIFICATION Broadly speaking, system identification is the art and science of using measurements obtained from a system to characterize the system. The characterization

More information

Adaptive Flux-Weakening Controller for IPMSM Drives

Adaptive Flux-Weakening Controller for IPMSM Drives Adaptive Flux-Weakening Controller for IPMSM Drives Silverio BOLOGNANI 1, Sandro CALLIGARO 2, Roberto PETRELLA 2 1 Department of Electrical Engineering (DIE), University of Padova (Italy) 2 Department

More information

TigreSAT 2010 &2011 June Monthly Report

TigreSAT 2010 &2011 June Monthly Report 2010-2011 TigreSAT Monthly Progress Report EQUIS ADS 2010 PAYLOAD No changes have been done to the payload since it had passed all the tests, requirements and integration that are necessary for LSU HASP

More information

Digital Control of MS-150 Modular Position Servo System

Digital Control of MS-150 Modular Position Servo System IEEE NECEC Nov. 8, 2007 St. John's NL 1 Digital Control of MS-150 Modular Position Servo System Farid Arvani, Syeda N. Ferdaus, M. Tariq Iqbal Faculty of Engineering, Memorial University of Newfoundland

More information

Observer-based Engine Cooling Control System (OBCOOL) Project Proposal. Students: Andrew Fouts & Kurtis Liggett. Advisor: Dr.

Observer-based Engine Cooling Control System (OBCOOL) Project Proposal. Students: Andrew Fouts & Kurtis Liggett. Advisor: Dr. Observer-based Engine Cooling Control System (OBCOOL) Project Proposal Students: Andrew Fouts & Kurtis Liggett Advisor: Dr. Gary Dempsey Date: December 09, 2010 1 Introduction Control systems exist in

More information

Brushed DC Motor Microcontroller PWM Speed Control with Optical Encoder and H-Bridge

Brushed DC Motor Microcontroller PWM Speed Control with Optical Encoder and H-Bridge Brushed DC Motor Microcontroller PWM Speed Control with Optical Encoder and H-Bridge L298 Full H-Bridge HEF4071B OR Gate Brushed DC Motor with Optical Encoder & Load Inertia Flyback Diodes Arduino Microcontroller

More information

Classical Control Design Guidelines & Tools (L10.2) Transfer Functions

Classical Control Design Guidelines & Tools (L10.2) Transfer Functions Classical Control Design Guidelines & Tools (L10.2) Douglas G. MacMartin Summarize frequency domain control design guidelines and approach Dec 4, 2013 D. G. MacMartin CDS 110a, 2013 1 Transfer Functions

More information

Magnetic Levitation System

Magnetic Levitation System Introduction Magnetic Levitation System There are two experiments in this lab. The first experiment studies system nonlinear characteristics, and the second experiment studies system dynamic characteristics

More information

MEM380 Applied Autonomous Robots I Winter Feedback Control USARSim

MEM380 Applied Autonomous Robots I Winter Feedback Control USARSim MEM380 Applied Autonomous Robots I Winter 2011 Feedback Control USARSim Transforming Accelerations into Position Estimates In a perfect world It s not a perfect world. We have noise and bias in our acceleration

More information

7 Lab: Motor control for orientation and angular speed

7 Lab: Motor control for orientation and angular speed Prelab Participation Lab Name: 7 Lab: Motor control for orientation and angular speed Control systems help satellites to track distant stars, airplanes to follow a desired trajectory, cars to travel at

More information

Andrea Zanchettin Automatic Control 1 AUTOMATIC CONTROL. Andrea M. Zanchettin, PhD Winter Semester, Linear control systems design Part 1

Andrea Zanchettin Automatic Control 1 AUTOMATIC CONTROL. Andrea M. Zanchettin, PhD Winter Semester, Linear control systems design Part 1 Andrea Zanchettin Automatic Control 1 AUTOMATIC CONTROL Andrea M. Zanchettin, PhD Winter Semester, 2018 Linear control systems design Part 1 Andrea Zanchettin Automatic Control 2 Step responses Assume

More information

CONTROLLER DESIGN FOR POWER CONVERSION SYSTEMS

CONTROLLER DESIGN FOR POWER CONVERSION SYSTEMS CONTROLLER DESIGN FOR POWER CONVERSION SYSTEMS Introduction A typical feedback system found in power converters Switched-mode power converters generally use PI, pz, or pz feedback compensators to regulate

More information

Paul Schafbuch. Senior Research Engineer Fisher Controls International, Inc.

Paul Schafbuch. Senior Research Engineer Fisher Controls International, Inc. Paul Schafbuch Senior Research Engineer Fisher Controls International, Inc. Introduction Achieving optimal control system performance keys on selecting or specifying the proper flow characteristic. Therefore,

More information

MCE441/541 Midterm Project Position Control of Rotary Servomechanism

MCE441/541 Midterm Project Position Control of Rotary Servomechanism MCE441/541 Midterm Project Position Control of Rotary Servomechanism DUE: 11/08/2011 This project counts both as Homework 4 and 50 points of the second midterm exam 1 System Description A servomechanism

More information

Open Loop Frequency Response

Open Loop Frequency Response TAKE HOME LABS OKLAHOMA STATE UNIVERSITY Open Loop Frequency Response by Carion Pelton 1 OBJECTIVE This experiment will reinforce your understanding of the concept of frequency response. As part of the

More information

3-DIMENSIONAL AUDIO TRACKING SYSTEM Final Report for ECSE-4962 Control Systems Design

3-DIMENSIONAL AUDIO TRACKING SYSTEM Final Report for ECSE-4962 Control Systems Design 3-DIMENSIONAL AUDIO TRACKING SYSTEM Final Report for ECSE-4962 Control Systems Design Nicholas J. Di Liberto Daniel Fleiner Andrew LeBlanc Edward Tang April 28, 2004 Rensselaer Polytechnic Institute Abstract

More information

Rotary Motion Servo Plant: SRV02. Rotary Experiment #17: 2D Ball Balancer. 2D Ball Balancer Control using QUARC. Instructor Manual

Rotary Motion Servo Plant: SRV02. Rotary Experiment #17: 2D Ball Balancer. 2D Ball Balancer Control using QUARC. Instructor Manual Rotary Motion Servo Plant: SRV02 Rotary Experiment #17: 2D Ball Balancer 2D Ball Balancer Control using QUARC Instructor Manual Table of Contents 1. INTRODUCTION...1 2. PREREQUISITES...1 3. OVERVIEW OF

More information

Course Outline. Time vs. Freq. Domain Analysis. Frequency Response. Amme 3500 : System Dynamics & Control. Design via Frequency Response

Course Outline. Time vs. Freq. Domain Analysis. Frequency Response. Amme 3500 : System Dynamics & Control. Design via Frequency Response Course Outline Amme 35 : System Dynamics & Control Design via Frequency Response Week Date Content Assignment Notes Mar Introduction 2 8 Mar Frequency Domain Modelling 3 5 Mar Transient Performance and

More information

Servo Tuning Tutorial

Servo Tuning Tutorial Servo Tuning Tutorial 1 Presentation Outline Introduction Servo system defined Why does a servo system need to be tuned Trajectory generator and velocity profiles The PID Filter Proportional gain Derivative

More information

Temperature Control in HVAC Application using PID and Self-Tuning Adaptive Controller

Temperature Control in HVAC Application using PID and Self-Tuning Adaptive Controller International Journal of Emerging Trends in Science and Technology Temperature Control in HVAC Application using PID and Self-Tuning Adaptive Controller Authors Swarup D. Ramteke 1, Bhagsen J. Parvat 2

More information

A Searching Analyses for Best PID Tuning Method for CNC Servo Drive

A Searching Analyses for Best PID Tuning Method for CNC Servo Drive International Journal of Science and Engineering Investigations vol. 7, issue 76, May 2018 ISSN: 2251-8843 A Searching Analyses for Best PID Tuning Method for CNC Servo Drive Ferit Idrizi FMI-UP Prishtine,

More information

Elements of Haptic Interfaces

Elements of Haptic Interfaces Elements of Haptic Interfaces Katherine J. Kuchenbecker Department of Mechanical Engineering and Applied Mechanics University of Pennsylvania kuchenbe@seas.upenn.edu Course Notes for MEAM 625, University

More information

Lab 2: Quanser Hardware and Proportional Control

Lab 2: Quanser Hardware and Proportional Control I. Objective The goal of this lab is: Lab 2: Quanser Hardware and Proportional Control a. Familiarize students with Quanser's QuaRC tools and the Q4 data acquisition board. b. Derive and understand a model

More information

Comparative Study of PID and Fuzzy Controllers for Speed Control of DC Motor

Comparative Study of PID and Fuzzy Controllers for Speed Control of DC Motor Comparative Study of PID and Fuzzy Controllers for Speed Control of DC Motor Osama Omer Adam Mohammed 1, Dr. Awadalla Taifor Ali 2 P.G. Student, Department of Control Engineering, Faculty of Engineering,

More information

Teaching Mechanical Students to Build and Analyze Motor Controllers

Teaching Mechanical Students to Build and Analyze Motor Controllers Teaching Mechanical Students to Build and Analyze Motor Controllers Hugh Jack, Associate Professor Padnos School of Engineering Grand Valley State University Grand Rapids, MI email: jackh@gvsu.edu Session

More information

CHAPTER 4 PID CONTROLLER BASED SPEED CONTROL OF THREE PHASE INDUCTION MOTOR

CHAPTER 4 PID CONTROLLER BASED SPEED CONTROL OF THREE PHASE INDUCTION MOTOR 36 CHAPTER 4 PID CONTROLLER BASED SPEED CONTROL OF THREE PHASE INDUCTION MOTOR 4.1 INTRODUCTION Now a day, a number of different controllers are used in the industry and in many other fields. In a quite

More information

Ver. 4/5/2002, 1:11 PM 1

Ver. 4/5/2002, 1:11 PM 1 Mechatronics II Laboratory Exercise 6 PID Design The purpose of this exercise is to study the effects of a PID controller on a motor-load system. Although not a second-order system, a PID controlled motor-load

More information

Module 08 Controller Designs: Compensators and PIDs

Module 08 Controller Designs: Compensators and PIDs Module 08 Controller Designs: Compensators and PIDs Ahmad F. Taha EE 3413: Analysis and Desgin of Control Systems Email: ahmad.taha@utsa.edu Webpage: http://engineering.utsa.edu/ taha March 31, 2016 Ahmad

More information

Intermediate and Advanced Labs PHY3802L/PHY4822L

Intermediate and Advanced Labs PHY3802L/PHY4822L Intermediate and Advanced Labs PHY3802L/PHY4822L Torsional Oscillator and Torque Magnetometry Lab manual and related literature The torsional oscillator and torque magnetometry 1. Purpose Study the torsional

More information

Laboratory Assignment 5 Digital Velocity and Position control of a D.C. motor

Laboratory Assignment 5 Digital Velocity and Position control of a D.C. motor Laboratory Assignment 5 Digital Velocity and Position control of a D.C. motor 2.737 Mechatronics Dept. of Mechanical Engineering Massachusetts Institute of Technology Cambridge, MA0239 Topics Motor modeling

More information

CDS 101/110a: Lecture 8-1 Frequency Domain Design

CDS 101/110a: Lecture 8-1 Frequency Domain Design CDS 11/11a: Lecture 8-1 Frequency Domain Design Richard M. Murray 17 November 28 Goals: Describe canonical control design problem and standard performance measures Show how to use loop shaping to achieve

More information

Embedded Robust Control of Self-balancing Two-wheeled Robot

Embedded Robust Control of Self-balancing Two-wheeled Robot Embedded Robust Control of Self-balancing Two-wheeled Robot L. Mollov, P. Petkov Key Words: Robust control; embedded systems; two-wheeled robots; -synthesis; MATLAB. Abstract. This paper presents the design

More information

CHAPTER 3 WAVELET TRANSFORM BASED CONTROLLER FOR INDUCTION MOTOR DRIVES

CHAPTER 3 WAVELET TRANSFORM BASED CONTROLLER FOR INDUCTION MOTOR DRIVES 49 CHAPTER 3 WAVELET TRANSFORM BASED CONTROLLER FOR INDUCTION MOTOR DRIVES 3.1 INTRODUCTION The wavelet transform is a very popular tool for signal processing and analysis. It is widely used for the analysis

More information

GE423 Laboratory Assignment 6 Robot Sensors and Wall-Following

GE423 Laboratory Assignment 6 Robot Sensors and Wall-Following GE423 Laboratory Assignment 6 Robot Sensors and Wall-Following Goals for this Lab Assignment: 1. Learn about the sensors available on the robot for environment sensing. 2. Learn about classical wall-following

More information

profile Using intelligent servo drives to filter mechanical resonance and improve machine accuracy in printing and converting machinery

profile Using intelligent servo drives to filter mechanical resonance and improve machine accuracy in printing and converting machinery profile Drive & Control Using intelligent servo drives to filter mechanical resonance and improve machine accuracy in printing and converting machinery Challenge: Controlling machine resonance the white

More information

EE 482 : CONTROL SYSTEMS Lab Manual

EE 482 : CONTROL SYSTEMS Lab Manual University of Bahrain College of Engineering Dept. of Electrical and Electronics Engineering EE 482 : CONTROL SYSTEMS Lab Manual Dr. Ebrahim Al-Gallaf Assistance Professor of Intelligent Control and Robotics

More information

CHAPTER 2 PID CONTROLLER BASED CLOSED LOOP CONTROL OF DC DRIVE

CHAPTER 2 PID CONTROLLER BASED CLOSED LOOP CONTROL OF DC DRIVE 23 CHAPTER 2 PID CONTROLLER BASED CLOSED LOOP CONTROL OF DC DRIVE 2.1 PID CONTROLLER A proportional Integral Derivative controller (PID controller) find its application in industrial control system. It

More information

FUZZY LOGIC CONTROL FOR NON-LINEAR MODEL OF THE BALL AND BEAM SYSTEM

FUZZY LOGIC CONTROL FOR NON-LINEAR MODEL OF THE BALL AND BEAM SYSTEM 11th International DAAAM Baltic Conference INDUSTRIAL ENGINEERING 20-22 nd April 2016, Tallinn, Estonia FUZZY LOGIC CONTROL FOR NON-LINEAR MODEL OF THE BALL AND BEAM SYSTEM Moezzi Reza & Vu Trieu Minh

More information

Using CME 2 with AccelNet

Using CME 2 with AccelNet Using CME 2 with AccelNet Software Installation Quick Copy (with Amplifier file) Quick Setup (with motor data) Offline Virtual Amplifier (with no amplifier connected) Screen Guide Page 1 Table of Contents

More information

Dr Ian R. Manchester

Dr Ian R. Manchester Week Content Notes 1 Introduction 2 Frequency Domain Modelling 3 Transient Performance and the s-plane 4 Block Diagrams 5 Feedback System Characteristics Assign 1 Due 6 Root Locus 7 Root Locus 2 Assign

More information

Design of Compensator for Dynamical System

Design of Compensator for Dynamical System Design of Compensator for Dynamical System Ms.Saroja S. Chavan PimpriChinchwad College of Engineering, Pune Prof. A. B. Patil PimpriChinchwad College of Engineering, Pune ABSTRACT New applications of dynamical

More information

A Machine Tool Controller using Cascaded Servo Loops and Multiple Feedback Sensors per Axis

A Machine Tool Controller using Cascaded Servo Loops and Multiple Feedback Sensors per Axis A Machine Tool Controller using Cascaded Servo Loops and Multiple Sensors per Axis David J. Hopkins, Timm A. Wulff, George F. Weinert Lawrence Livermore National Laboratory 7000 East Ave, L-792, Livermore,

More information

Nonlinear Control Lecture

Nonlinear Control Lecture Nonlinear Control Lecture Just what constitutes nonlinear control? Control systems whose behavior cannot be analyzed by linear control theory. All systems contain some nonlinearities, most are small and

More information

CDS 101/110a: Lecture 8-1 Frequency Domain Design. Frequency Domain Performance Specifications

CDS 101/110a: Lecture 8-1 Frequency Domain Design. Frequency Domain Performance Specifications CDS /a: Lecture 8- Frequency Domain Design Richard M. Murray 7 November 28 Goals:! Describe canonical control design problem and standard performance measures! Show how to use loop shaping to achieve a

More information

of harmonic cancellation algorithms The internal model principle enable precision motion control Dynamic control

of harmonic cancellation algorithms The internal model principle enable precision motion control Dynamic control Dynamic control Harmonic cancellation algorithms enable precision motion control The internal model principle is a 30-years-young idea that serves as the basis for a myriad of modern motion control approaches.

More information

Figure 1: Unity Feedback System. The transfer function of the PID controller looks like the following:

Figure 1: Unity Feedback System. The transfer function of the PID controller looks like the following: Islamic University of Gaza Faculty of Engineering Electrical Engineering department Control Systems Design Lab Eng. Mohammed S. Jouda Eng. Ola M. Skeik Experiment 3 PID Controller Overview This experiment

More information

ME375 Lab Project. Bradley Boane & Jeremy Bourque April 25, 2018

ME375 Lab Project. Bradley Boane & Jeremy Bourque April 25, 2018 ME375 Lab Project Bradley Boane & Jeremy Bourque April 25, 2018 Introduction: The goal of this project was to build and program a two-wheel robot that travels forward in a straight line for a distance

More information

SECTION 6: ROOT LOCUS DESIGN

SECTION 6: ROOT LOCUS DESIGN SECTION 6: ROOT LOCUS DESIGN MAE 4421 Control of Aerospace & Mechanical Systems 2 Introduction Introduction 3 Consider the following unity feedback system 3 433 Assume A proportional controller Design

More information

Ball and Beam. Workbook BB01. Student Version

Ball and Beam. Workbook BB01. Student Version Ball and Beam Workbook BB01 Student Version Quanser Inc. 2011 c 2011 Quanser Inc., All rights reserved. Quanser Inc. 119 Spy Court Markham, Ontario L3R 5H6 Canada info@quanser.com Phone: 1-905-940-3575

More information

elevation drive. The best performance of the system is currently characterized by 3 00 steps.

elevation drive. The best performance of the system is currently characterized by 3 00 steps. Submillimeter Array Technical Memorandum Number 4 December 6, 996 Performance of the Elevation Drive System Eric Keto Abstract This memo reports on measurements and modeling of the performance of the elevation

More information

In-Depth Tests of Faulhaber 2657CR012 Motor

In-Depth Tests of Faulhaber 2657CR012 Motor In-Depth Tests of Faulhaber 2657CR012 Motor By: Carlos Arango-Giersberg May 1 st, 2007 Cornell Ranger: Autonomous Walking Robot Team Abstract: This series of tests of the Faulhaber 2657CR012 motor were

More information

AN APPROACH TO IMPROVE THE PERFORMANCE OF A POSITION CONTROL DC MOTOR BY USING DIGITAL CONTROL SYSTEM

AN APPROACH TO IMPROVE THE PERFORMANCE OF A POSITION CONTROL DC MOTOR BY USING DIGITAL CONTROL SYSTEM ISSN (Online) : 2454-7190 ISSN 0973-8975 AN APPROACH TO IMPROVE THE PERFORMANCE OF A POSITION CONTROL DC MOTOR BY USING DIGITAL CONTROL SYSTEM By 1 Debargha Chakraborty, 2 Binanda Kishore Mondal, 3 Souvik

More information

Neural Network Predictive Controller for Pressure Control

Neural Network Predictive Controller for Pressure Control Neural Network Predictive Controller for Pressure Control ZAZILAH MAY 1, MUHAMMAD HANIF AMARAN 2 Department of Electrical and Electronics Engineering Universiti Teknologi PETRONAS Bandar Seri Iskandar,

More information

Sfwr Eng/TRON 3DX4, Lab 4 Introduction to Computer Based Control

Sfwr Eng/TRON 3DX4, Lab 4 Introduction to Computer Based Control Announcements: Sfwr Eng/TRON 3DX4, Lab 4 Introduction to Computer Based Control First lab Week of: Mar. 10, 014 Demo Due Week of: End of Lab Period, Mar. 17, 014 Assignment #4 posted: Tue Mar. 0, 014 This

More information

Automatic Control Systems 2017 Spring Semester

Automatic Control Systems 2017 Spring Semester Automatic Control Systems 2017 Spring Semester Assignment Set 1 Dr. Kalyana C. Veluvolu Deadline: 11-APR - 16:00 hours @ IT1-815 1) Find the transfer function / for the following system using block diagram

More information

Advanced Motion Control Optimizes Laser Micro-Drilling

Advanced Motion Control Optimizes Laser Micro-Drilling Advanced Motion Control Optimizes Laser Micro-Drilling The following discussion will focus on how to implement advanced motion control technology to improve the performance of laser micro-drilling machines.

More information