Abstract

In this paper, a structure design scheme of intelligent replacement device for the ultrahigh voltage (UHV) converter transformer valve-side bushing is put forward, and its size is determined according to the actual size of domestic converter station valve hall and UHV converter transformer valve-side bushing. Moreover, the weak links in its working state are analyzed by finite element method to ensure the safety and reliability of the structure. Based on the spinor theory, the forward kinematics and Jacobian matrix model of the manipulator are established, and the analytical solution of inverse kinematics is derived. In order to analyze the accuracy of the intelligent replacement manipulator for the UHV converter transformer valve-side bushing, considering that the end actuator of the robot arm is under heavy load, the absolute positioning accuracy and repeated positioning accuracy are analyzed. In addition, the corresponding error model is established, the least square method is proposed to identify the error model, and the influence of the error caused by the load on the repetition accuracy is analyzed. Finally, the whole process simulation in ROS provides data support for the calculation of repetitive precision and verifies the feasibility of the intelligent replacement device for the UHV converter valve-side bushing.

1. Introduction

With the increasing demand for energy, it is estimated that the annual global power generation will exceed 38, 000 TWH by 2040. In order to meet this demand, long-distance large-capacity transmission technology is particularly important [14]. The stability and reliability of converter transformer is the key to the smooth progress of high voltage transmission, and the failure of UHV converter transformer valve-side bushing is one of the main reasons affecting the stability and reliability of converter transformer [57]. Therefore, when the bushing fails, it should be replaced in time.

At present, the general process of replacing the UHV valve-side bushing is as follows: first, the bushing is towed by a trailer, and the manual on-site adjustment makes the bushing towed to the appropriate position. Two cranes are needed for installation, and the bushing is lifted to prevent the sloshing speed from being slow. If the hoisting angle is required, the angle needs to be adjusted continuously with the help of the angle measuring instrument until the bushing reaches the installation position [8]. The disassembly process is opposite to the installation process. The whole process is complicated and time consuming [811]. As shown in Figure 1 below is the field diagram of the removal of the bushing on the side of the UHV converter valve in a converter station. Therefore, it is of great practical significance to design a manipulator that can intelligently replace the UHV converter transformer valve-side bushing in the valve hall. The core of intelligent replacement is to accurately locate the spatial position of the bushing.

The performance of the manipulator is mainly evaluated from two aspects: positioning accuracy and repeatability [1215]. The positioning accuracy and repeatability of the manipulator are called the accuracy of the manipulator. The former can be summarized as the ability of the manipulator to accurately achieve any position and pose at any possible speed relative to the base coordinate system along any path in the workspace. Repeatability means that the manipulator can accurately reach the last position along the last traversing path, and the repeatability of the manipulator is also called the repetitive positioning accuracy of the manipulator [13]. The main method to improve the accuracy of the manipulator is to calibrate it [14, 1618], which proves that a newly designed manipulator should be calibrated before it can be put into use [1921].

In this paper, an intelligent replacement manipulator for the UHV converter transformer valve-side bushing is designed, which can be used in the valve hall. In order to solve the problem of spatial positioning of bushing, the calibration of intelligent replacement manipulator for the bushing based on spinor theory is put forward, and a more practical expression of repeated positioning accuracy is put forward. It is worth noting that the research structure can provide a basis for the future development of the intelligent replacement manipulator for the UHV converter transformer valve-side bushing.

The rest of the article will be organized according to the following. Section 2 introduces the overview of manipulator calibration. Section 3 describes the mechanical structure, working principle, and process of the intelligent replacement manipulator for the UHV converter transformer valve-side bushing. In Section 4, the forward and inverse kinematics analysis is carried out by using the product of exponentials (POE) formula, and the velocity Jacobian matrix is obtained. Section 5 puts forward the basis for establishing the error model. Section 6 simulates the process of intelligent replacement equipment in ROS system. Finally, Section 7 summarizes the article and puts forward the space for future development.

2. Literature Review

The key to realize the intelligent replacement of the UHV converter valve-side bushing is that the end actuator of the manipulator can independently and accurately locate the space position of the bushing hoisting hole and can accurately install the new bushing along the original path, after removing the damaged bushing. This puts forward the requirements for calibrating the robot arm for intelligent replacement of the side bushing of the UHV converter valve and improving its absolute positioning accuracy and repeated positioning accuracy. In reference [22], the concept of robot elastic calibration is put forward, which is helpful to realize high-precision positioning under high load, which indirectly shows the importance of repeated positioning accuracy of high-load manipulator.

The calibration of manipulator is a comprehensive process of modeling, measurement, identification, and compensation [14, 2326]. This paper mainly considers the problems of modeling and identification. Modeling is to model the kinematics of the manipulator and derive the error model according to the kinematics model. There are three commonly used methods to establish kinematic models, namely, Denavit–Hartenberg (D-H) method, Modified Denavit–Hartenberg (MDH) method, and POE method.

At present, D-H parameter method is commonly used in manipulator calibration to establish kinematics model because its method is simple and easy to use. The D-H parameter method is used to establish the kinematic model in reference [2730], but the D-H parameter method has a defect that cannot be ignored, that is, its motion can only revolve around the x-axis and z-axis, but cannot express the motion about the y-axis [26], which makes the singularity problem when the two continuous joints are parallel or nearly parallel, and the calculation process of the kinematic model of the manipulator with multidegree of freedom is complex and inefficient. In view of the shortcomings of the D-H parameter method, the MDH method has good kinematic characteristics and can find the forward and inverse solutions of the kinematic model [13, 3133], but the singularity problem is still a great challenge. In order to solve the singularity problem of kinematic model, the model based on POE not only has the characteristic of no singularity but also can deal with any combination of rotating joint and prism joint, which ensures the completeness of the model, and has been widely used in recent years [30, 3437].

The identification process of manipulator calibration is the parameter identification of the error model. The error model should meet the requirements of continuity, completeness, and minimization [38]. The most commonly used error model identification algorithms are least square method, maximum likelihood estimation method, genetic algorithm, and extended Kalman filter algorithm [14].

The least square method that realizes the identification of error parameters by finding the method of minimizing the error between theoretical data and actual data. It is a simple optimization algorithm, and its biggest advantage is short running time and strong search ability, so it is widely used. In the literature [38, 39], the least square method is used to accurately identify the error model derived from the kinematics model based on POE. The simulation and experimental results verify the reliability of the algorithm.

The biggest advantage of maximum likelihood estimation method for parameter identification is good convergence, simple iterative method, and strong practicability [14]. The maximum likelihood estimation method is used to identify the parameters of the error model in reference [40]. The experimental results verify the feasibility of this method, but the identification effect is not good for complex kinematic error models.

Genetic algorithm (GA) is a method to find the optimal solution by simulating natural evolution, and it is a research hotspot in recent years. In reference [41], genetic algorithm is used to identify the kinematic error model of parallel mechanism, and the experimental results show that the calibration accuracy is greatly improved. However, compared with the former two algorithms, the process of genetic algorithm is complex, and the accuracy guarantee is not higher than the former two methods, so the utilization rate of genetic algorithm in the parameter identification of manipulator error model is not high.

The main function of the extended Kalman filter algorithm is to use the linear model to approach the nonlinear model and combine the initial attitude estimation of the next time with the measured feedback to get a more accurate attitude estimation at this time. In reference [33], the extended Kalman filter algorithm is used to identify the kinematic parameters, and the positioning accuracy of the calibrated robot has been significantly improved. However, compared with the least square method, this algorithm is more complex and changeable and is more suitable for high-precision and small load situations.

In this paper, based on the kinematics model established by spinor theory, the forward kinematics equation is derived using POE formula. The error model is established according to the kinematics model, and the least square method is used to identify the parameters of the repeated error model.

3. Overall Equipment Design

3.1. Structural Design

For the intelligent replacement device for UHV converter transformer valve-side bushing with precision guarantee, its kinematic mechanism, actuator, driving mechanism, and sensor distribution should be comprehensively considered according to the specific conditions. In this paper, the intelligent replacement device is designed according to the classical layout of the common valve hall in China. The structure and dimensions of the valve hall are shown in Figure 2. The overall structure design scheme of the intelligent replacement device is shown in Figure 3.

The total length of the intelligent replacement device is about 6800 mm, the total width is about 2750 mm, and the total height is about 3000 mm when the hook distance adjustment arm 10 falls. The equipment is mainly composed of chassis walking system, distance adjustment mechanism, and disassembly system. Wherein, the chassis walking mechanism is composed of a mobile chassis 1 and a balance leg 12, and the distance adjusting mechanism is composed of a longitudinal sliding groove 2, a vertical telescopic support frame 3, and a horizontal sliding groove 4. The disassembly system consists of a rotating turntable 5, a luffing boom chassis 6, a luffing boom translation cylinder 7, an upper hook 8, an upper laser scanner 9, a hook distance telescopic boom 10, a luffing boom 11, a lower laser scanner 13, and a lower hook 14.

3.2. Mechanical Arm Mechanism Design

The intelligent replacement device for the UHV converter transformer valve-side bushing needs to complete the action in the valve hall. The balance leg 12 is propped up during operation to ensure that the equipment center of gravity of the entire system is within the mobile chassis, preventing the car from turning over during operation and lifting it up during nonoperation. The manipulator has 7 degrees of freedom, including 2 rotational degrees of freedom and 5 mobile degrees of freedom. When working, the end actuator can be ensured to reach any position in the workspace, so that the replacement of the bushing can be completed. The specific calculation process of manipulator kinematics is introduced in Section 4.

The load-bearing weight of the manipulator is large and the mechanical size is large. According to the working characteristics and requirements of bushing hoisting, the mechanical arm configuration of traditional crane is improved, and special hook distance telescopic boom 10 and luffing boom 11 are designed. The distance adjustment mechanism is used for rough adjustment of the position and posture of the disassembly system relative to the bushing. The translational joint was used, and longitudinal sliding groove 2, horizontal sliding groove 4, and vertical telescopic support frame 3 were used to adjust the posture of XYZ in three directions. The disassembly system is used to accurately adjust the position and posture of the intelligent disassembly equipment and to disassemble and reinstall the bushing. Luffing boom chassis 6 can be rotated in the horizontal plane by rotating turntable5, that is, along the Z axis. The rotation of luffing boom 11 is controlled by the hydraulic cylinder, which can realize the rotation on the vertical surface, that is, the rotation along the Y axis. Luffing boom translation cylinder 7 enables the extension of luffing boom 11, enabling hook distance telescopic boom 10 to reach the corresponding height of the removable valve-side bushing. Each end of the hook distance telescopic boom 10 contains two telescopic hydraulic cylinders, which can be adjusted between upper hook 8 and lower hook 14 to accommodate the distance between the lifting holes at both ends of the bushing. In addition, the upper and lower hooks are, respectively, located at the end of the secondary hydraulic cylinder of hook distance telescopic boom 10, and the rope fastened by the hook is in the secondary hydraulic cylinder. The two-stage hydraulic cylinders at both ends of hook distance telescopic boom 10 are equipped with upper laser scanner 9 and lower laser scanner 13, respectively. In this project, lower laser scanner 13 is mainly used to scan the bushing and obtain point cloud data, and through the coordinated movement of each joint of the intelligent disassembly equipment, lower laser scanner 13 is driven to move along the axis of the bushing. When covering a uniform cover on the bushing, upper laser scanner 9 can be used at the same time to further improve accuracy.

3.3. Work Flow

The intelligent disassembly device for the UHV converter valve-side bushing designed in this paper, when working, the hook uses a rope to lift the bushing through the lower hoisting hole and the lifting hole near the equalizing cap. Through the telescopic arm of the bushing between the joints of the intelligent disassembly platform, the movement along the axis of the bushing can be realized. Figure 4 shows the working diagram of the intelligent disassembly device for the of UHV converter valve-side bushing.

First, the position is roughly adjusted to control the intelligent bushing replacement device to the appropriate position, in which the telescopic boom 2 is roughly parallel to the bushing 5 and the transverse distance of the bushing 5 is about 0.5 m. The positioning of the bushing 5 is calculated, and the laser scanner installed on the intelligent replacement device scans the bushing 5 and calculates the cylindrical parameters. Then the position of the intelligent replacement device is accurately adjusted according to the calculation results, and the hook 3 is mounted to the hoisting hole of the bushing 5. Then the telescopic boom 2 automatically moves along the axis of the bushing 5 to pull out the bushing 5; manual intervention is carried out through the console to ensure no collision; and the disassembled bushing is placed on the transfer vehicle. Finally, the disassembly is complete.

During reinstallation, the position and posture are adjusted first, and after the bushing is mounted to the intelligent bushing replacement device on the side of the UHV converter valve, the intelligent replacement device adjusts the position and posture of the bushing according to the orientation determined when the bushing is removed. Then, the angle of the bushing is precisely adjusted so that the axis of the bushing is consistent with that of the outlet device. Finally, slowly return the bushing, according to the data recorded when removing the bushing, constantly adjust the angle of the bushing to ensure accurate operation, when the bushing is about to be inserted, continue to hoist the bushing after getting the permission of the operator; after the bushing reaches the installation position, the installation flange of the bushing and the outlet device are installed through the method, and the reinstallation is completed.

3.4. Structural Simulation

When the intelligent replacement device is working, it bears a lot of weight. Some of the hoisted valve-side bushing weighs 1700 kg. The interface of the hook and boom are the weak links of the whole structure and may be deformed and broken under the gravity action of the bushing and the manipulator. Therefore, it should be analyzed by finite element method. The material is 45# steel, the mass density is , the Young’s elastic modulus is , the Poisson’s ratio is 0.29, the shear modulus is , and the yield strength is . The finite element analysis is carried out in the WORKBENCH module of ANSYS17.0.

Considering the particularity of the terminal executive structure and the connected joint, in order to make the analysis structure more reliable, the connected joint is extended to the maximum arm length (at this time, the structural reliability is the weakest), and the safety factor is added when the external force is applied to both ends of the joint, that is, the external force . The simulation results are shown in Figure 5, the maximum principal stress is 99.479 MPa less than the yield strength, the maximum shear stress is 53.300 MPA, the maximum deformation along the x-axis is 0.059237 mm, and the maximum deformation is 1.3688 mm.

In the actual working condition, there is a problem of uneven force at both ends of the actuator at the end of the manipulator for the intelligent replacement of the bushing on the side of the UHV converter valve. In order to make the results more meaningful, the finite element simulation is carried out on the force of 2 : 1 at both ends. That is, the force at one end is 8500 N and the force at the other end is 17000 N. As shown in Figure 6, the maximum principal stress is 107.57 MPa less than the yield strength, the maximum shear stress is 58.011 MPa, the maximum deformation along the x-axis is 0.053988 mm, and the maximum deformation is 1.5654 mm.

It can be seen from the above simulation results that the mechanical structure meets the strength conditions and the design is reliable.

4. Kinematic Analysis

The establishment of an appropriate kinematic model is one of the important factors to determine the positioning accuracy of the manipulator [42]. In this paper, spinor theory is used for kinematic modeling. This method only needs to determine the basic coordinate system S and the tool coordinate system T, which is much easier than D-H parameter method and MDH method, and the calculation process is based on the basic coordinate system, so it is not easy to make mistakes, and the calculation efficiency is greatly improved. In this section, on the basis of the kinematics model established by the spinor theory, the forward kinematics equation is derived by using the POE formula. Then, the geometric relationship is established according to the kinematics model, and the analytical solution of inverse kinematics and velocity Jacobian matrix are derived.

4.1. Forward Kinematics Solution

The kinematics model is established using the spinor theory. The vertical telescopic support frame of the intelligent replacement manipulator is designed as a parallel structure in order to reduce weight, but it only executes the command of moving along the z-axis, so the modeling can be treated as a series mechanism. The kinematic model is established under the initial position and posture, and the coordinate system diagram is shown in Figure 7.

For revolute joints, the motion spin quantity is expressed as follows:where is the unit vector in the direction of the axis of motion spinor, and is any point on the axis[43]. For moving joints,where is the unit vector of the direction of movement. All vectors and points are described relative to the base coordinate system S. By combining the motions of each joint, we can find that the forward kinematic mapping (Q is joint space, SE (3) and Euclidean group) as shown in the following formula:

The above formula is also known as the POE formula for the forward solution of robot kinematics. The rotation matrix can be expressed by Rodrigues formula as follows:

If , then the antisymmetric matrix symmetric is defined as (operator^ represents antisymmetric matrix):

The vector can be expressed by the following expression:

can be expressed by the following matrix:where .

According to Chasles’s theorem, the motion of any rigid body can be realized by rotating around an axis and moving parallel to that axis. To solve the kinematic model of intelligent disassembly equipment, it is necessary to obtain the motion spinor of each joint. The motion axis of intelligent disassembly equipment is established on the base coordinate system , and the θ=0 of each joint is taken, that is, the initial position. After the hook as an example, because the end of the intelligent disassembly equipment is a rope structure, so take out the rope mouth as the end, and establish the tool coordinate system.

When θ=0, the basic coordinate system and the tool coordinate system are converted towhere is the distance between joint axis and is the distance of Y direction between joint axis and is the distance of Z direction between joint axis and is the distance of Y direction between joint axis and is the distance of X direction between joint axis and is the distance of Y direction between joint axis and . The first, second, third, sixth, and seventh joints of the intelligent disassembly equipment are mobile joints, and the corresponding motion spinor coordinates are

The fourth and fifth joints of the intelligent disassembly equipment are rotating joints, and the unit vectors corresponding to the axis direction of the joints are

With as the coordinate system, the coordinate points on each joint axis are

From the motion spinor of the rotation joint can be obtained as follows:

Its POE form iswhere Let ; then,

Therefore, the matrix index of each joint is in the form of

The kinematics equation of intelligent disassembly equipment can be obtained by combining the motion of seven joints.

Therefore,where

At the same time, , and are the workspaces of intelligent disassembly equipment in the direction of XYZ in the space, respectively. Where .

4.2. Inverse Kinematics Solution

The inverse solution of the kinematics model based on spinor theory is mainly solved by Paden–Kahan subproblem. However, the Paden–Kahan subproblem is generally used in the solution of rotating joints, or in the solution of manipulator with no more than three degrees of freedom [44], and the calculation process is complex and the amount of calculation is large. The analytic geometry method can be used to solve the manipulator with more moving joints, and it is easy to understand and has high computational efficiency. Therefore, this paper uses the method of analytic geometry to solve the inverse kinematics solution of the manipulator.

From the schematic diagram of the manipulator coordinate system, we can know that is the angle vector rotating along the X axis, and the geometric relationship of the YZ plane can be obtained, as shown in Figure 8.

can be obtained from the geometric relation diagram.

When calculating , since rotates around the Z axis, the period diagram can be obtained from the geometric relation of the XY plane, as shown in Figure 9.

According to the geometric relationship, we can get

Or:

When solving and , considering that both and are moving vectors, their sagittal diagrams are similar, as shown in Figure 10.

According to the geometric relationship, we can get

Similarly,

To solve , we might as well project the kinematics diagram to the YZ plane, and the geometric relation diagram can be obtained as shown in Figure 11.

It can be obtained from the geometric relationship:

When solving and , it is noticed that and are moving vectors along the y-axis and x-axis.

So far, the inverse kinematics solution has been solved.

4.3. Speed Jacobian Matrix Based on POE Formula

Because the intelligent replacement device for the UHV converter transformer valve-side bushing has a large load on the end actuator and the installation precision is required, it is necessary to avoid the situation that the speed of the end actuator is too fast. Therefore, it is necessary to analyze the velocity relationship between each joint and the end actuator. The velocity Jacobian matrix is a mapping matrix describing the joint velocity of the robot to the end actuator, and it is the differential of the forward mapping of kinematics. The natural and clear description of the robot Jacobian matrix is obtained by using the POE formula, which can highlight the geometric characteristics of the mechanism and avoid the deficiency of local parameter representation.

According to Section 4.1, the POE formula of the kinematic forward mapping of the manipulator of the intelligent replacement device for the UHV converter transformer valve-side bushing is as follows:

Then the instantaneous speed in space of the actuator at the end of the robotic arm can be represented by the following motion spiral:

Combining the characteristics of the kinematic chain, we can getwhere the value of i is from 1 to 7, denotes the velocity of joint, and the operator [^] of square brackets denotes antisymmetric matrix.

It can be seen that there is a linear relationship between the speed of the end actuator and the speed of each joint. Using the motion helix coordinates, the above equation can be written as follows:where

The matrix is called the spatial Jacobian matrix of the robot. For any configuration θ, it maps the joint velocity vector to the corresponding end actuator speed, where the operator represents the mapping relation, such as the inverse operation of the , the operator is the inverse operation of , that is,

Then it is transformed into a motion spiral coordinate:where is the adjoint matrix of .

Then the space Jacobian matrix of the robot becomeswhere .

5. Distance Error Model Analysis

The intelligent replacement of the side bushing of the UHV converter valve the joint of the actuator at the end of the manipulator is a linear structure. When considering the absolute positioning accuracy of the end actuator, the error is expressed by the distance between the end actuator and the hoisting point, because the two points should coincide in theory, so the definition of distance error is given. When defining the repetition accuracy, the deviation between the simulation fitting track under no load and the actual track under load is the error because the end actuator installs and disassembles the side bushing of the UHV converter valve walking a straight track, the repetition error is represented by the maximum deviation distance between the two tracks.

5.1. Absolute Positioning Accuracy Error Model

It can be seen from Section 4.1 that the pose of the end effector is , and its generalized position coordinate is .

It can be seen from the forward solution mapping relationship, .

Abbreviate the above formula as , then.where is a rack distortion error, which is unrecognizable in the simulation phase, and itself is a minimal error, which is not considered in this paper.

Therefore, expand the above formula to obtain

Where means that there are i error terms in the multiplication and is called the first-order error. Since the error itself is a relatively small number, the second-order and above error terms are ignored here, and the position and attitude error of the actuator at the end of the manipulator can be approximately expressed as

To simplify further, we can getwhere J is the identification Jacobian matrix.

It can be expressed as a least squares problem. . Where is the error.

According to Chasles’s theorem, the motion of any rigid body can be realized by rotating around an axis and moving parallel to that axis. Then the geometric error of any joint I can be expressed as . Where is the point on the axis of rotation of joint and is the unit vector of the direction of the axis of rotation of joint . Therefore, the error of the generalized coordinate of the end actuator of the manipulator can be expressed as

The addition of here is because the parameter error caused by the joint variable motion is taken into account, which makes the position error expression of the end actuator of the manipulator more comprehensive.

The definition of distance error is expressed aswhere refers to the distance error between the nominal distance between the two points i and j on the indicator trajectory and the actual distance between the two points i and j on the actual trajectory; refers to the nominal distance between two points i and j; and refer to distance errors between the coordinate components corresponding to the points j and i on the nominal trajectory and the point j and i on the actual trajectory.where refers to the position vector of the actuator at the end of the manipulator at the two points of j and i and refers to the position error vector at the two points of j and i.

Formulas (39)–(41) above indicates the position distance error of the actuator at the end of the manipulator.

5.2. Repeated Positioning Accuracy Error Model

Considering the large load bearing at the end of the robot arm for the intelligent replacement of the bushing on the side of the UHV converter valve, it may lead to a large trajectory deviation between no load and heavy load, resulting in the collision of the bushing back installation and other problems; therefore, the repeated positioning accuracy of the intelligent replacement manipulator for the UHV valve-side bushing should be calibrated. The spatial straight line equation can be expressed aswhere K(m, n, l) is the direction vector of space straight line and L() is the point on the space straight line. The cylindrical bushing fitting algorithm has been introduced in detail and verified in reference [11]. The offset angle between the simulated axis and the actual axis is represented by . In this paper, the process simulation of UHV converter valve-side bushing in ROS will be introduced in detail in the next chapter. The comparison between the simulated axis fitting data and the actual data in 3D modeling is shown in Table 1.

Combined with the actual working process of the intelligent replacement of the mechanical arm on the side of the UHV converter valve, it can be known that the ROS fitting bushing axis should be used as the instruction track, that is, the instruction track is

From the structural simulation results of Section 3.4, it can be seen that the axis deformation occurs due to the action of bushing gravity during the reinstallation of the manipulator, and then the error is introduced. The schematic diagram of its trajectory error is shown in Figure 12. If the actual trajectory is , then the error of the two trajectories can be expressed as a least square problem:

Let denote the instruction track segment and denote the deformation of the joint connected to the end actuator of the manipulator under heavy load. Then the maximum distance error of the two tracks when the forces on both ends of the end actuator are equal can be expressed aswherein, .

Substituting it, there is .

When the force at both ends of the end effector is 2 : 1, the maximum distance error can be obtained by bringing into the equation (45) again.

The above represents the maximum distance error that may occur in the case of heavy load when the reinstallation trajectory of the UHV converter valve-side bushing is unchanged in the simulation case. The calculation results report that the repetitive error caused by overloading cannot be ignored and should be taken into account in the actual calibration.

6. Intelligent Replacement Simulation of Valve-Side Bushing

Since the size of the intelligent replacement device is too large to carry out the actual experiment, it can only be verified in the form of simulation. In this paper, ROS operating system is used for simulation to verify the feasibility of intelligent replacement device and replacement process. The simulation system is built in ROS Kinetic Kame, Moveit, and Gazebo 9 under Ubuntu 16.04 and consists of a converter transformer and smart replacement equipment.

In the ROS operating system, URDF documents are used to describe the hardware structure of the robot, which is a file using XML format. The URDF document can define the coordinate system, shape parameters, color and other information of each link, and connect the parent link and child link to each other through the joint. When the structure of each equipment is designed in the three-dimensional drawing software and exported to URDF documents, the relationship between the joint coordinate systems is established by spinor theory. The parallel structure of vertical telescopic support frame is changed to the series structure with two-stage lifting hydraulic cylinder because the simulation of parallel mechanism cannot be realized in ROS, as shown in Figure 13.

According to the work flow of the intelligent replacement device, it is divided into five states: stretching state, scanning state, disassembly state, reloading state, and closing state. When the intelligent replacement equipment is not working, it is closed, that is, the motion joints are 0, as shown in Figure 7. The stretching state is the state in which the equipment is extended to the coarse adjustment position after the equipment is turned on, which is shown in Figure 14. The scanning state refers to the working process in which the user teaches the equipment to scan the valve-side bushing and solve the bushing space parameters, which is shown in Figure 15. If the user teaches to scan once and the equipment scans again automatically, it can also be reduced to the scanning state. The disassembly state is the working process of removing the valve-side bushing after solving the bushing space parameters, and this process also includes the process of the worker removing the damaged bushing from the equipment. The reinstallation state is the process that the equipment reinstalls the good bushing to the converter transformer, and this process also includes the process that the worker hangs the bushing from the intelligent transfer trolley to the hook of the equipment. The closing state means that the equipment returns to its position when it is just turned on after completing the replacement task.

After the scanning process is completed, the completed laser point cloud data are obtained, which is shown in Figure 16.

The running result is displayed on the terminal page after the scan, and the fitting result is shown in Figure 17. The figure shows the number of scans, the number of point clouds, the fitted axis parameters, and the radius of the valve-side bushing. Specifically, the number of scans of the virtual laser profiler is 39, but the effective data are 15, and the total number of 3D point clouds obtained correctly is 9540.

The comparison between ROS fitting bushing parameters and 3D model bushing parameters is shown in Table 1. 3D model bushing is a model in 3D composition software. The bushing parameters are obtained directly from the 3D composition software. The bushing model in ROS is imported and generated from 3D composition software, and the position relationship between the intelligent replacement equipment coordinates and the valve-side bushing coordinates is consistent.

At the end of the scanning process and solving the bushing axis parameters, the intelligent replacement equipment will enter the disassembly state, reinstallation state, and close state, and the ROS simulation process of each state is shown in Figures 18 to Figure 20. In the process of disassembly and reinstallation, the end tool coordinate system of the intelligent replacement equipment is fixed with the valve-side bushing instead of the hook bushing in the real replacement environment because of the limitation of the simulation platform. In fact, compared with the way of hanging the hook to install the bushing, the fixed connection method requires higher precision of the bushing parameters. The process of replacing the old bushing with the new bushing at the end of the disassembly state cannot really replace the bushing, so this process is replaced by the intelligent replacement equipment that carries the valve-side bushing away from the original position of the valve-side bushing. The process of replacing the new bushing is shown in Figure 21.

The above simulation results show the feasibility of the intelligent replacement device for the UHV converter transformer valve-side bushing proposed in this paper, and the simulation results also provide data support for the calculation of theoretical repetition accuracy.

7. Conclusion

In this study, an intelligent replacement device for UHV converter transformer valve-side bushing is presented. Because the end executive joint arm is longer and the load is heavy, it is a relatively weak joint in the whole structure, so we carry out finite element analysis when the arm length reaches the maximum and give a safety factor of 1.5. The simulation analysis shows that the structure meets the strength condition.

Based on the spinor theory, the forward kinematics and Jacobian matrix model are derived, and the inverse kinematics of the manipulator is solved by the analytic geometry method, which provides a mathematical basis for the establishment of the error model. The absolute positioning error and repeated positioning error model of the intelligent replacement manipulator for the UHV converter transformer valve-side bushing are established, and the least square method is proposed to identify the error parameters.

The load simulation of the theoretical model shows that the repetition errors of the theoretical model with equal force at both ends and 2 : 1 force at both ends are 1.3701 mm and 1.5663 mm, respectively. These data cannot be ignored in the actual situation, and the repeated positioning accuracy under the influence of gravity should be taken into account when calibrating all kinds of heavy-duty intelligent manipulators.

The simulation results suggest the feasibility of the proposed intelligent replacement device for the UHV converter transformer valve-side bushing. The intelligent replacement equipment can be operated in the valve hall to complete the replacement of the bushing without pulling the converter out of the running position and without removing other accessories. With the application of this replacement scheme, the replacement of bushing can also be realized under adverse weather conditions such as strong wind, at the same time, the use of special working tools such as cranes and tractors can be avoided, and the difficulty of construction can be reduced. In addition, when the two valve-side sleeves are installed side by side in the vertical direction, one of the sleeves can be removed arbitrarily, and there is no need to remove the other sleeves first.

Data Availability

The data used to support the findings of this study are included within the article.

Conflicts of Interest

The authors declare that they have no conflicts of interest.