Open access peer-reviewed chapter

Stewart-Gough Platform: Design and Construction with a Digital PID Controller Implementation

Written By

Flabio Dario Mirelez-Delgado, José Ronaldo Díaz-Paredes and Miguel Abraham Gallardo-Carreón

Submitted: 16 December 2019 Reviewed: 19 February 2020 Published: 24 November 2020

DOI: 10.5772/intechopen.91817

From the Edited Volume

Automation and Control

Edited by Constantin Voloşencu, Serdar Küçük, José Guerrero and Oscar Valero

Chapter metrics overview

1,515 Chapter Downloads

View Full Metrics

Abstract

This document presents the design of a digital PID control for a Stewart-Gough platform, delimited by six degrees of freedom (DoF) that allow the final effector to have displacement in the XYZ axes and rotation with warpage, pitch, and yaw restrictions. It includes the study and resolution of the direct and inverse kinematics of the platform, as well as the workspace described by the final effector and its corresponding simulation of movements and joints to study extreme points and possible singularities. From the definition of characteristics, the CAD design generated from the generalized mathematical model of the public domain, and the general selection of materials for the construction of the functional prototype, a study of applied forces is generated to observe the points with stress concentrators, the safety factor, and possible deformations. The estimation of the sampling period for the selection of the microcontroller and an approximate definition of the response time are also considered. The development of this prototype and its documentation are proposed as didactic material for the study, design, and control of parallel mechanisms.

Keywords

  • Stewart-Gough platform
  • PID control
  • parallel robots
  • inverse kinematics
  • CAD design

1. Introduction

When talking about industrial robotics, one of the first associated thoughts is about the serial robots that are highly applicable to this field; however, parallel robots also have a great importance and range of applications in this environment. Among its most important characteristics, its high load/power ratio is distinguished. In the case of the Stewart-Gough platform, this characteristic lies in its possibility of distributing the load in approximately six equal parts, whereby the total load capacity of the parallel robot approximates six times the load capacity of each actuator individually.

The Stewart platform is a parallel type manipulator that involves a configuration of six degrees of freedom, and each degree of freedom corresponds to an actuator. The six actuators can be linear or angular and join the bottom of the robot, which has no mobility, called a base with the part that does have mobility, the final effector. Due to this configuration, the Stewart-Gough platform has high rigidity, which can be translated into greater precision.

The final effector is the most interesting part of the robot, since its position and even orientation are the characteristics that determine if the robot is able to meet the precision necessary to implement and satisfy a need, whether industrial, educational, research, etc. It can have different applications, for example, orientation of satellites, flight simulators, and shakers (or also called agitators that are part of the chemistry laboratory instruments), among others.

This document explains the design, construction, and implementation of a discrete PID control to a Stewart-Gough platform.

Advertisement

2. Preliminaries

2.1 Control

To enter into definition of what control is, we begin by explaining what a process is, which is referred to as a set of equipment or devices attached or implemented to perform operations that help fulfill a task [1]. To enforce this task, a series of additional devices are needed that regulate the process in general, which are called a control system as a whole [1].

Ogata [2] mentions four methods (belonging to the classical control or also called conventional control) for the design of a controller. These are the following:

  • Root place

  • Frequency response

  • PID controllers

  • Modified PID controllers

In general, a control system needs a mathematical model that describes its behavior when receiving inputs [2]. For the Stewart platform, it can be determined by inverse kinematics [3].

The PID controller is the most common form of feedback, was an essential element of the first governors, and became a model or standard tool when process control emerged in the 1940s [4]. Consider a control loop of an input and an output. The block diagram [5] is shown in Figure 1 .

Figure 1.

SISO system block diagram.

Of the PID control family, there are members that involve the three actions: proportional (P), integral (I), and derivative (D) [5].

There are two control design techniques that are analog and digital, and for this they work with continuous time and discrete time systems, respectively. Many of the systems are described by differential equations, and analog control design techniques have become popular. Also most of the controllers are made of digital systems [6]. You can also discretize analog controllers to obtain digital controllers. Next, characteristics of control systems are mentioned, analog and digital [7]:

  • Analog

    • Noise is a problem in all signal transmissions.

  • Digital

    • They have the ability to reject noise.

    • It is easy to implement and modify digital controllers simply by changing the coefficient values.

A digital or discrete time system is a dynamic system in which one or more variables may vary only at certain times called sampling indicated by kT (k = 0,1,2, ..., n) [8].

The block diagram of a digital control system is shown in Figure 2 [9].

Figure 2.

Block diagram of a digital control system.

Advertisement

3. Parallel robots

The term parallel robot, also known as closed-chain robot or parallel manipulator, basically consists of a fixed base attached to an end effector or mobile base which can perform its movement based on the movement of the actuators that are located in such a way that they close the kinematic chain between both bases [9]. The principle of operation initially arose with James E. Gwinnett, who designed a platform for the entertainment industry in the 1928 patent application [10]. However, it was not until 1940 when W. Pollard designed the first industrial sparallel robot for spray painting processes [11] ( Figures 3 and 4 ).

Figure 3.

James E. Gwinnett patent (industrial entertainment platform).

Figure 4.

First parallel robot designed by W. Pollard.

After the first advances of the Stewart platforms applied to industrial processes, some companies began to make variants of these platforms, such as the case of the Redifon company that was asked by Lufthansa German Airlines to produce a simulator of flight, with the initial model designed for its then new Boeing 727 fleet. This simulator model included three axes, which gave the mechanism the mobility needed to recreate the behavior of the aircraft. Redifon is currently in service since its commissioning in 1949, when it began with the production of flight simulators, trainers, and the development of new techniques [12] ( Figure 5 ).

Figure 5.

Flight simulator developed by Redifon for the Boeing 747 model.

Advertisement

4. Inverse kinematics

Inverse kinematics is a mathematical modeling of a manipulator, either serial (open kinematic chain) or parallel (closed kinematic chain). Such modeling requires as input parameters the position of the final effector in order to calculate the angles that exist between links and thus determine the position of each actuator in the reference XYZ coordinate space [13]. It should be noted that the final effector is the part of interest of any robot.

The fixed coordinates ( F xyz ) are placed in the center of the fixed base, and the other mobile coordinate system ( M uvw ) is positioned in the center of the mobile platform ( Figure 6 ).

Figure 6.

Isometric and top view of the platform with coordinate systems and actuator junction points.

Points F i and M j are the points of the joints between one actuator end with the fixed base and the other end of the actuator with the movable base, respectively. The separation angles between points F 1 and F 2 , F 3 and F 4 , and F 5 and F 6 are denoted by θ b . Similarly, the angle of separation between points M 1 and M 2 , M 3 and M 4 , and M 5 and M 6 is denoted by θ p . To locate the links or points F i , use Eq. (1):

F i = F Xi F Y F Zi = r b cos μ i r b sen μ i 0 E1

And for points M j :

M j = M Uj M Vj M Wj = r p cos λ j r p sen λ j 0 E2
Advertisement

5. Direct kinematics

As mentioned in the previous chapter, reverse kinematics needs the position of the final effector as input parameters to calculate the angles between links of the robot. So, the direct kinematics is the counterpart of inverse kinematics, since its initial data are the angles established between each actuator and what is calculated is the position of the final effector. A very common method of using is Denavit-Hartenberg, explained by Barrientos, which follows a 16-step algorithm to get a single homogeneous transformation matrix from the premultiplication of submatrices of homogeneous transformation. The steps of this methodology are the following [14]:

DH1. Number the links starting with 1 (first mobile link in the chain) and ending with n (last mobile link). The fixed base of the robot will be numbered as link 0.

DH2. Number each joint starting with 1 (the one corresponding to the first degree of freedom) and ending in n.

DH3. Locate the axis of each joint. If this is rotary, the axis will be its own axis of rotation. Yes it is prismatic, it will be the axis along which the displacement occurs.

DH4. To i from 0 to n 1 , place the axis z i on the axis of the joint i + 1 .

DH5. Place the origin of the base system S 0 at any point on the z 0 axis. The axes x 0 and y 0 are they will place so that they form a dextrogyre system with z 0 .

DH6. For i from 1 to n 1 , place the system S 0 (in solidarity with the link) at the intersection of the axis z i with the normal line common to z i 1 and z i . If both axes were cut, it would be located S i at the point of cut. If they were parallel S 0 , it would be located in the joint i 1 .

DH7. Place x i on the normal line common to z i 1 and z i .

DH8. Position y i so that it forms a dextrogyre system with z i and x i .

DH9. Position the system S n at the end of the robot so that z n matches the direction of z n 1 and x n be normal to z n 1 and z n .

DH10. Get θ i as the angle to be rotated around z n 1 so that x n 1 and S i remain parallel.

DH11. Get d i as the distance measured along z i 1 , which should be displaced S i so that x i 1 and x i were aligned.

DH12. Obtain α i as the distance measured along x i (which would now match x i 1 ), so that the new S i 1 would have to be moved so that its origin coincided with S i .

DH13. Get α i as the angle that should be turned around x i (which would now match x i 1 so that the new S i 1 totally coincided with S i .

DH14. Obtain the transformation matrices i 1 A i defined as:

i 1 A i = c θ i c α i s θ i s α i s θ i a i c θ i s θ i c α i c θ i s α i c θ i a i s θ i 0 s α i c α i d i 0 0 0 1 E3
Advertisement

6. Microcontroller selection

One of the main parameters to be defined within the control system implementation is the sampling period T, which is a design element that allows different components to be selected among the most important ones such as the microcontroller. There are several methods for obtaining it; however, for this project the selection has been considered using the method described in [8] which selects the period based on the commitment between the following factors:

  1. The calculation time of the processor

  2. Numerical precision in the implementation

  3. Loss of information in the sampling

  4. Response to disturbances

In general, the sampling period must be selected in compromise between a range of time that avoids the deterioration of the quality of the control that can produce a high value of T and the amount of calculations necessary to execute the control algorithm with small values that can produce information loss and frequency overlap (aliasing).

In these, three cases are considered, which can be monitored based on the available elements, the ease of calculation, and the nature of the project.

  • Take the bandwidth of the system: This considers the system as a closed loop system in which each of the elements and their respective frequency are raised. From this, the bandwidth of the system that will serve as a reference for the base frequency of sampling is determined.

  • Establishment time required for the transient response: This method can be performed by simulation or experimental, since it considers obtaining a response time based on the reach of 63.3% of the final value in the transient response. In [16] an oscilloscope was used to measure the response curve and the Tao time by applying a pulse signal and a mechanism adapted to the actuators. In turn, a great advantage of this method is to observe the response curve and the actual efficiency of the actuators with respect to the data provided by the manufacturer.

  • Select the highest frequency component: This is a method that allows an estimation of the sampling period based on the system component that requires sampling more frequently. Because currently the plant calculations have not been performed, nor have the components been obtained for obtaining transient response, this is considered the most successful method for estimating the sampling period.

Once the method is defined, the component that requires the highest working frequency is selected. For the selection, the actuators are directly discarded, because they only require a PWM pulse that varies depending on the desired position that does not exceed 1.25 ms, which is why the components to be considered will be the gyroscope sensors and the resistive panel that will measure the external forces applied to the final effector and the external movements applied to the platform in inclined planes.

Later, the selected sensors and their detailed characteristics will be described; however, in this section, only the basic principle of their operation will be seen, which will follow up the methodology described above to obtain the sampling time.

The sensor placed at the top of the final effector and responsible for measuring the movements of moving objects will be a five-wire resistive panel (can be found in 4, 5, or 8 wires), which consists of a partially conductive layer (resistive) that is applied evenly to the panel. Conductive bus bars are protected with a silver paint through the opposite edges of the panel. Rigid and flexible panels are mounted with bus bars perpendicular to each other as shown in Figure 7 . The sensor measurement is done by applying a force on the ITO layer which generates a voltage gradient across one of the layers and measuring the tension in the other layer. This gradient is normally produced by grounding a bus bar and applying +5 V on the other bar, which produces a voltage gradient on the axes that cross the panel; this applies only to one layer, the rigid layer, while the other layer is the sensitive one in both measurements.

Figure 7.

Configuration of the layers of a resistive panel.

The measurement is done sequentially in which the events are presented with the voltage gradient on the x-axis and the voltage in the sensor layer is measured; followed by this, the voltage gradient is switched to the y-axis, and another measurement is taken of the same sensor layer. To determine the sampling rate of the resistive panel, the use that will be given must be considered, for example, if it is to be used as a human interface where the contact will be a finger, the necessary resolution is not very high. Being a 6-inch-long panel and the contact resolution is 2 in (average finger size), then the analog-to-digital converter (ADC) must represent 30 points. With 5 bits, 32 points can be represented, so an ADC converter of 8 to 12 bits is sufficient in this case and a sampling rate of 10 samples per second is sufficient. In the case of wanting to make a more accurate representation in the panel using pens or objects of greater precision, the touch screen should have a resolution of at least 320 points. This gives a converter of at least 9 bits (29 = 512 levels).

The sampling rate of the touch screen controller in this case must be higher so as not to lose information on the movements being captured; therefore, a speed of 100 samples per second would suffice. For the actual position in movements on the inclined plane, the MPU-6050 model is contemplated within the gyroscope selection with something important to point out, and among its main features is the precise capture of fast and slow movement; it has a scale range of 250/500/1000/2000 °/s. That is why, by requiring a greater sampling range per second than the resistive screen, this gyroscope will be selected as the component with the highest working frequency and which will be used to monitor the sampling time selection process. To measure the movements of the final effector, it is not considered necessary to work at the maximum capacity of the gyroscope because the maximum angle of action in warping and pitching will be ± 20 according to [22], since the configuration of the angular actuators. Considering that the system performs an extreme compensation movement of 40 by programming a minimum sampling of 250, the movements should be carried out with a speed of 1/250 (0.004) s, which is approximate to the speed of the angular actuator that varies between 0.0028 and 0.002 s/g (characteristic that will be seen later), which is why it is considered that the sensor at its maximum power would be wasting most of the sampling because the actuators would not be able to compensate for the said signal ( Figure 8 ).

Figure 8.

Gyroscope sensor and accelerometer MPU-6050.

Despite having sufficient sampling time, the case in which the sensor configured at its maximum capacity of 2000/s will be used (in which case the movements made on it should be 0.0005 seconds, this value is higher to the tests to which it will be subjected) to have an extra safety factor in the selection of the sampling; this leads to the next step, which mentions the cases in which overlaps (aliasing) or loss of information with a too large period may occur ( Figures 9 and 10 ). To prevent these problems from large sampling periods, the Nyquist theorem [22] is applied, which dictates that the sampling frequency Ws, defined as 2 π / T where T is the sampling period, is greater than 2 W c (frequency to be sampled), that is:

W s > 2 W c

Figure 9.

Signal overlap (aliasing).

Figure 10.

Signal sampled by Nyquist theorem.

From this, it is mentioned in [8] that it should be considered as a general rule that the system must be sampled between 8 and 12 times during a cycle of the dampened frequency of the transient response if the system is under-absorbed or between 8 and 12 times during the time of establishment of the response if the system is overdamped. In which case, the minimum of this factor will be taken because it is desired to obtain a system with an under-absorbed or over-absorbed response.

Once the gyroscope is selected as the component with the highest frequency within the system, the largest measuring range provided by this device is taken as a reference, and as already mentioned, the sensor has a capacity to measure 2000/s and deliver it. A digital signal by I2C protocol, however, although this sampling configuration will not be required when incorporated into the system (since it exceeds the value of the speed performed by the actuators, in addition to requiring an ADC with higher resolution than even would be exceeded because the workspace of the platform is limited and does not exceed 100) is considered as the base sampling frequency because it is considering the critical case in which you want to obtain the highest frequency required for. The processor fulfills this task.

It is important to note that W s = 16 kHz will be the selected working frequency that requires at least the processor to operate optimally in the sampling of the gyroscope signal; this is because later considerations will be made (of which currently are ignored to simplify calculations) such as the incorporation of resistive screen sampling in the ADC, the working frequency of the actuators individually, and in the kinematic chain, as well as may or may not affect the size of the program along the lines of code because when considering the implementation of a conventional microcontroller, the programming must be done in series and not in parallel.

Once an estimated time is defined for the sampling period, the microcontroller options (or microprocessor with minimum system) that meet these requirements are searched. Likewise, some of the main characteristics that they present and are required by other system components are compared, such as PWM peripherals for the six actuators, the I2C communication ports for the gyroscope, the ADC channels for the resistive panel, as well as its resolution and an extra feature that would be the type of assembly due to the didactic purpose of the platform, since when pretending to be manipulated by students of the institution, against any problem that may arise, the components are easy to replace.

It is currently considered the best candidate for the ATMega328P microprocessor, either with a minimum system implemented or using the nomadic development card Pro + that incorporates it, and being a THT type assembly is easy replacement, as well as being economical and accessible. The microprocessor incorporates six ADC channels, of which one will be destined for the resistive panel and the other two directly coincide with the SCL and SDA channels through which I2C communication is performed. In addition, six PWM channels (one channel for each actuator) that are distributed in ports B and D are required for actuator control ( Figure 11 ).

Figure 11.

ATmega328P microprocessor peripherals incorporated in NomadaPro + development card.

Advertisement

7. Mathematic model

The Stewart platform mechanism, until the mid-1980s, mostly maintained the design of the triangular platform connected by spherical joints to three linear actuators adjustable in length. This configuration linked the base (whose design can vary between a triangular and hexagonal shape) with the final effector (which maintains its triangular shape) by means of the actuators coinciding two by two at the vertices of the final effector with a total of six different points contained in the base plane. These configurations are denoted as 3-3 Stewart platform and 6-3 Stewart platforms [23], respectively, as can be seen in Figure 12 .

Figure 12.

Different configurations of the Stewart-Gough platform [23].

Considering a point of coincidence in spherical joints in the triangular platform, it restricted the mobility in the manipulator, producing overstrain and a reduced workspace; from this, the configuration is obtained whose base retains the regular or semi-regular hexagonal shape and the final effector is generated from an equilateral triangle with the trimmed vertices known as 6-6 Stewart platform. The said design allows some parameters and components to be varied according to the needs and/or specifications, such as the actuators that can go from being linear to angular by means of a crank-crank type conditioning mechanism. Likewise, the type of joint can be modified, in which as is the case, spherical and non-universal joints will be used. Once the different configurations of the structure of the Stewart-Gough platform are present, the configuration 6-6 Stewart platform was selected, which allowed a better manipulation of the final effector, which avoids as much as possible the efforts by singularities, and given the application, a large workspace is not necessary as it is proposed to carry out movements that are not so abrupt for the stabilization of objects that move on the surface, application of external forces, or movements on the inclined plane.

From this, it is observed that there is a wide variety of mechanical configurations for this type of manipulator with the 6-6 Stewart platform kinematic chain according to the previous selection. This kinematic structure considers a variant known as 6-SPS that is observed in Figure 13 , where 6 refers to the number of degrees of freedom of the robot and SPS comes from the English spherical-prismatic-spherical referring to the leg from point to point, where the joints at the ends are prismatic and the link between them is a prismatic joint [23]. Once this configuration is selected that allows spherical joints to be placed on both sides of each actuator, a modification is made to the actuators such that instead of a prismatic joint between the joints relative to the linear actuator, it is replaced by a link element between both unions and the extension movement is generated by a configuration with angular actuators, as will be seen later in the left, thus remaining a configuration like the one presented in Figure 14 . Using the Grubler criterion [13], the number of degrees of freedom on a 6-SPS type platform can be determined using the equation:

m = λ n j 1 + i = 1 j f i I f E4

where: m = degrees of freedom of the system.

Figure 13.

Stewart 6-SPS platform [23].

Figure 14.

Stewart 6-SPS platform with angular actuators [18].

λ = degrees of freedom of the space where the mechanism is, λ = 3, two-dimensional and λ = 6 for the spatial case.

n = number of fixed links of the mechanism, including the base and the final effector.

j = number of joints in the mechanism.

f i = relative degrees of movement per board.

I f = number of passive degrees of freedom of the mechanism.

Substituting Eq. (5), you have:

m = 6 14 18 1 + i = 1 12 3 + i = 1 6 1 6 = 6 E5

The workspace, also known as the field of action, is the area or spatial volume that the robot can describe when it reaches extreme points. This described volume is determined by the dimensions, shape, and movement of the joints that make it up, as well as the degrees of freedom (depending on the configuration and type of robot), and on some occasions the applied control system can also influence [15].

Although the robot has a defined workspace, it is not confirmed that such space can be described in any orientation. There are a number of points, usually the most extreme and the closest to the origin that can be accessed only with certain configurations, and some others can be reached in any orientation. This as already mentioned depends a lot on the type of configuration of the robot.

One of the disadvantages that parallel robots have over serial ones is the limited description of the workspace; this is due to the restrictions that one joint has over another in the closed kinematic chain. In the case of the Stewart-Gough platform, you can make the proposal of a workspace described by the final effector from which the dimensions of the different elements that make up the parallel robot (base, joints, platform) are obtained, legs, actuators, and horn. On the other hand, you can obtain a supposed workspace based on the selection of components to evaluate at each point of the joints, the actuators, and links, the possible interferences that can be caused between them, as well as the possible restrictions of each meeting [16].

There are several methods to obtain the measurements of each element of the Stewart-Gough platform either by describing trajectories as they do in [19] or generating a proposal from a radius of action; this is because the said platform has a design focused on minimally invasive coronary bypass surgery. The proposal of measures can also be made based on the generation of algorithms by a method observed in [17]. Several of these methods to describe the workspace of a Stewart-Gough platform in a graphic form are based on the discretization of the Cartesian space and then evaluate the length of the links according to the actuators and thus determine that they are within the range and detect interference between actuators and/or meetings and the possible restrictions of each meeting. This method can also include simulations by implementing and evaluating the Jacobian matrix to define a movement and joint capacity [18]. Despite the variations between models of the Stewart-Gough platform, the inverse kinematics and the workspace in general have the same behavior and the same description of trajectories, as mentioned in the calculation of the inverse kinematics. The same can be used for all regardless of the type of actuators. This of course may vary slightly according to the dimensions, configuration, and/or elements used for its elaboration; however, the shadow described by the said workspace is projected with a great similarity between them. Using the methodology outlined in [19], Figure 15 is generated, which corresponds to the definition of dimensions of the Stewart-Gough platform, making the consideration that the servomotors are located parallel to each other. For this, it is based on the definition of the base, that when the Stewart-Gough Platform was previously proposed with approximate dimensions at a volume that encloses it from 30 to 35 cm, an internal diameter coincides with the axis of the servos is established, it has a measure of 25 cm because the standard digital servomotors have a depth of approximately 5 cm ( Figures 16 and 17 ).

Figure 15.

Description of the trajectory of the Stewart platform for CABG surgery [19].

Figure 16.

Workspace described by the Stewart-Gough platform using the Jacobian matrix [18].

Figure 17.

Workspace of the Stewart-Gough platform in isometric view [16].

Once the base is defined, the required workspace is raised. In principle, the design of the platform is not required to describe paths with too much depth or around a radius as is done in [19]; in this case the important data to consider would be the angles of warping and pitching inclination, since they will be intended for stabilizing sliding objects on the surface of the platform.

For this situation, one of the conditions of the state space is proposed, which would be described by the yellow line in Figure 15 , where the inclination angle is proposed of 20 present in most Stewart platforms with documented angular actuators and which is considered sufficient inclination for the stabilization of objects sliding on the surface as can be seen in [15]. It is worth mentioning that this is an extreme reach position that is physically not possible to achieve and would cause singularities, which is why it is recommended not to bring the final effector to these horizons in which the platform would lose stability and control may lose efficiency in its execution.

Finally, the possible restrictions generated by the articulation of the spherical joint are added ( Figure 15 ) since according to the table in Annex F, the working angle (depending on the size of the joint) is between ± 13 and ± 18; therefore, leaving a value of 14, it is observed that the opposite angle corresponds to 76 that are assigned in the internal area of the trapezoid generated with the frontal view since in principle when placing the actuators parallel to each other, it seems to be a four-bar mechanism that can make 360 movements. However, there are restrictions generated by the other links that have to respect that angle of work of the patella. This is how the values of link L = 15, the diameter of the platform Dp = 18, the diameter of the base Db = 25, and a height in the original position of 14.5 are finally obtained.

The parts that move the platform itself are called legs and are composed of a rod, threaded at each end, so that two kneecaps (upper and lower) are placed ( Figures 16 18 ).

Figure 18.

Dimensions of the Stewart-Gough platform according to workspace. (a) Platform in front view with actuators parallel to each other. (b) Leg with spherical joints in side view.

The lower ball joints connect each of the rods with their respective actuator (in this case it is the servomotor) by means of what will be referred to as horn or actuator arm. Servomotors are considered part of the “fixed base” or simply called a base [20].

To facilitate the reader’s understanding, the parts just explained on the CAD model designed for this project are presented in Figure 19 . The arms have a hole in their geometric center used to join each arm with the axis of their respective servomotor. At the end of the horn, the lower kneecaps are coupled to create a joint and join the horn with the rod (also called link), so that it allows the movement to be transmitted.

Figure 19.

Parts of the base. Ball joints (red ovals), rods (yellow lines), actuator arms or horns (blue line) and servomotors (green arrows).

Such movement is a conversion of angular movement to linear movement; this is a distinguishing feature of this project to the configuration that has the classic Stewart platform.

At the upper end of each of the rods, there is a joint to another kneecap, similar to the lower part of the rod.

On the other hand, there are a total of six other ball joints on the platform, connecting the closed kinematic chain to the platform. The platform is also often called the final effector, and this is the most interesting part of any serial or parallel robot.

Because the inverse kinematics is unique for parallel manipulators, the same inverse kinematics calculated on the Stewart platform [16] will be taken using the same views and changing some labels.

The coordinate systems F , of the base row, and M , of the final effector, will be renamed by B (base) and P (platform), respectively, and also the labels of the unions F i and M j for unions B i and P j , respectively. Taking into account the modifications explained in this paragraph, Eqs. (6, 7) presented in the theoretical framework will be as follows:

B i = B Xi B ij B Zi = r b cos μ i r b sen μ i 0 E6
P i = P Ui P Vi P Wi = r p cos λ i r p sen λ i 0 E7

Figure 20 presents the schematic diagram of the reference systems: Look at Figure 21 , this indicates the joint positioning diagram, assuming that the uv plane of the reference system P is parallel to the plane xy . Both coordinate systems ( P and B ) are centered and separated by a vertical distance from the base, that is, on the z-axis (height of the platform or the final effector with respect to the coordinate system B ): For the simulation process of external forces applied to the Stewart-Gough platform, the CAD design generated from the measurements was used, from which an estimate of the measurements for the base, platform, links, and horn of the servo. While a standard model was used for servomotors and spherical joints taking a CAD design from the public domain, within a platform called GRABCAD. For the generation of the design study, we worked with a CAD design software and finite element study that allowed us to observe some important aspects such as deformations, stress concentrators, and safety factor estimated for the platform in case of applying a force of overload in the final effector. Because the current work does not focus on the design of the platform as it is but of the controller for it, the pertinent calculations for a certain deformation or safety factor are not considered within the objectives. The following simulations were generated from an estimate of approximate real materials; this is because the suppliers of these products do not specify the material used.

Figure 20.

Schematic diagram of new reference systems.

Figure 21.

Joint positioning diagram.

To obtain results closer to reality, each element of the general assembly was assigned its respective material, as already mentioned, estimating the specific polymer or alloy of each metal. Starting with the bases and the final effector, in which case it was assigned an ABS plastic since, for practicality and speed, the options of laser cutting or 3D printing are currently considered, likewise, the servomotors are also considered in ABS. For the joints and links, the majority of suppliers handle metallic products for RC cars; therefore, a galvanized metal was assigned for its relative low cost and ease of machining. Finally, aluminum is mostly used for the servomotor horn, and therefore 1060 alloy aluminum is assigned.

Once each material is determined, the rest of the simulation conditions are defined starting with each restriction of the mechanism, and once all its position relationships are defined, the only geometric restriction will be the base on its lower face simulating that said platform is embedded on a regular horizontal surface. For the application of applied forces, an estimation of distributed load on the final effector is made considering that on average each actuator (depending on the manufacturer) can bear nominally 15 kg/cm of torque, and being the 3 cm servo horns, it is considered that each actuator supports a total of 5 kg at its end, for which a total force of 30 kg is applied. In the previous figure, it can be seen that within the mechanism in general, most of the effort is generated in the legs of the platform, while the largest almost imperceptible concentrator is at the junction between the leg and the servomotor horn, just where applies the highest torque due to the use of angular actuators. Despite this, it can be seen within the graph that there is no critical effort that may represent a risk of rupture ( Figure 22 ).

Figure 22.

von Mises stress study.

For the following study, the deformation in each part of the platform is contemplated; note that in both the stress study and the deformation study, the elements corresponding to the base do not undergo significant changes, however, the platform and the links deform from considerable way especially the part of the final effector that can become almost completely deformed. However, it is worth mentioning that CAD design software mostly exaggerates the results obtained from the simulation; this is to clearly appreciate the effects of the applied conditions, since in a real case the materials would tend to fracture rather than deform due to its low ductility. In which case, the greatest deformation present is only 32.2 mm. From the previous points, the safety factor is studied, where you can clearly see the elements of the mechanism where it is applied without considering the elements of the base, which, as observed in previous studies, has no tendency to break due which is contemplated embedded in a fixed surface and reinforced with each other. Therefore, in the legs, which are important for the performance of the mechanism, a safety factor of 3.4 is presented, which for the application that will be given to the Stewart-Gough platform is an acceptable value ( Figure 23 ). Finally, the study of applied efforts is carried out in the situation where the platform has a maximum load applied to the resistive screen in one of its vertices; this is mainly contemplated (a little ahead of the selection of components) to know how much you can resist the screen to the point of rupture which in which case would be the element on the platform with greater fragility. As shown in Figure 24 , the safety factor remains low at 0.45 and has a deformation of 1.12 cm, in which case, the CAD software deforms the part to demonstrate the displacement; however, in reality the panel would tend to fracture before having such deformation.

Figure 23.

Deformation study.

Figure 24.

Study of the safety factor.

Advertisement

8. Conclusions

The present document set out the objectives and the description of the partial result; from this, a favorable product was obtained regarding the characteristics of the system and the definition of its components.

Throughout the document the different points that led to the determination or adaptation of certain elements or characteristics of the work to be carried out are observed, this (as initially mentioned in the problem statement) was subject to change as more in The theme with the purpose of bringing the system closer to the desired characteristics, is by means of this method that it was possible to determine the components that would allow the generation of the CAD design and the electronic design sketch.

One of the proposed objectives was the calculation of inverse kinematics. When investigating more about the subject, it was concluded that it is possible to use the same one as described in [1], because for parallel manipulators with the same configuration, it is unique. Despite having replaced the linear actuators with angular ones, it has no impact on the calculation of the same, since the distance of interest is the vector that describes the collinear extension between the axis of the servomotor and its respective point of coincidence on the platform (upper kneecap) as shown in Figure 25 .

Figure 25.

Deformation and stress study of the Stewart-Gough platform applied to the resistive panel.

The maximum position and orientation parameters of a Stewart-Gough platform depend on the application given to this device. Since this project requires bringing a sliding object on the resistive panel to a desired position, it was determined that the suitable angle for this system is 20 for warping and 20 for pitching. To arrive at this characteristic, an estimation of measures was implemented based on the desired workspace, and the geometric and articular parameters were checked by simulations.

References

  1. 1. Roca A. Control Automtico de Procesos Industriales. Madrid, Spain: Diaz de Santos; 2014
  2. 2. Ogata K. Ingeniera de control moderna. Madrid: Pearson; 2010
  3. 3. Yaovaja K. Ball Balancing on a Stewart Platform using Fuzzy Supervisory PID Visual Servo Control. 2018 5th International Conference on Advanced Informatics: Concept Theory and Applications (ICAICTA) [Internet]. IEEE; August 2018. Available from: http://dx.doi.org/10.1109/icaicta.2018.8541349
  4. 4. Åström KJ. PID Control, de Control System Design. Santa Barbara, USA: CalTech; 2002. pp. 216-251
  5. 5. Mazzone V. Controladores PID. de Automatizacin y Control Industrial: Quilmes, Argentina, Universidad Nacional de Quilmes; 2002. pp. 1-11
  6. 6. Moudgalya KM. Digital Control. Wiley; 2007
  7. 7. Jaimes LEG. Control Digital Teora y Prctica. Medelln, Colombia: Politcnico Colombiano Jaime Isaza Dadavid; 2009
  8. 8. Ogata K. Sistemas de control en tiempo discreto. Minnesota: Prentice Hall; 1996
  9. 9. Rodriguez DAR, Diseo de una plataforma robtica paralela de 6 DOF para asistente quirrgico en cirugas de reconstruccin craneo-facial; 2010
  10. 10. Gwinnett JE. Amusement Device. Estados Unidos de America: Patentes; 1931
  11. 11. Pollard W. Spray Painting Machine. Estados Unidos de America: Patentes; 1940
  12. 12. Redifon, Another Redifon Flight Simulator Sold. Flight International, Crawley Sussex England; 1962
  13. 13. Martnez JMR. Las diferentes formas del criterio de Kutzbach-Grbler. Facultad de Ingeniera Mecnica, Elctrica y Electrnica: Salamanca, Gto; 2015
  14. 14. Barrientos A. Fundamentos de Robtica. New York, USA: McGraw-Hill; 2007
  15. 15. Ximena N, Alvarez G. Estudio, diseo y construccin de una plataforma robtica didctica tipo stewart aplicada al estudio de controladores difusos. Cuenca, Ecuador: Universidad Politcnica Salesiana; 2011
  16. 16. Acua HG, Dutra MS. Cinematica inversa y anlisis del espacio de trabajo de una plataforma. Stewart, Bucaramanga, Colombia: Universidad Autnoma de Bucaramanga; 2009
  17. 17. Chatterjee B. Design of a Semi-Regular Stewart Platform Manipulator for a Desired Workspace. Bangalore, India: Mechanical Engineering Department, Indian Institute of Science; 2009
  18. 18. Szufnarowski F. Stewart Platform with Fixed Rotary Actuators: A Low Cost Design Study. Bielefeld, Germany: E.E.U.U; 2018
  19. 19. Lazatevic Z. Feasibility of a Stewart Platform with Fixed Actuators as a Platform for CABG Surgery Device. E.E.U.U: New York, USA: Columbia University Department of Bioengineering; 2003
  20. 20. Fichter EF. A Stewart Platform-Based Manipulator: General Theory and Practical Construction. Oregon State University;

Written By

Flabio Dario Mirelez-Delgado, José Ronaldo Díaz-Paredes and Miguel Abraham Gallardo-Carreón

Submitted: 16 December 2019 Reviewed: 19 February 2020 Published: 24 November 2020