Keywords

These keywords were added by machine and not by the authors. This process is experimental and the keywords may be updated as the learning algorithm improves.

1 Introduction

The kinematics of cable robots and indeed all [14] parallel robots have been subject of research for a number of years. While inverse kinematics are trivial, forward kinematics are much more difficult to solve, especially within computational constraints such as real-time capability. In general, the forward kinematics of parallel robots can have 40 real solutions [1], which are numerically difficult to compute directly [2]. Other methods, more practical to implement, are thus consistent topics of research. Some rely on changing geometry [12], others on interval methods [7], and also on numerical optimization methods [3, 10].

With the increasing research on cable robots, and an ever increasing number of prototypes, precise information regarding achievable accuracy and methods of improvement have become more important. While accuracy and repeatability values achieved in the past are good, performance can still be improved. Methods include continuous calibration and inclinometers [4], general geometric calibration [8], and external sensors such as an expensive non-contact laser scanning system for Cartesian metrology used by the NIST Robocrane [13].

Robot kinematic models, both forward and inverse kinematics, have a direct impact on accuracy. Previous implementations [10] have usually assumed perfect points as base and platform connections. In practice cables are often guided along a pulley as shown in Fig. 1.

Taking into account of such pulleys in kinematics has been shown in existing models [9], but such models have yet to be implemented in real-time.

Real-time calculations pose a frequent challenge for forward kinematics especially when optimization methods are used whose convergence is not guaranteed. Hence research into convergence and computation time has been conducted [15].

In this paper an algorithm that takes winch pulleys into account is reviewed and implemented in a real-time environment. To evaluate this implementation experiments into the accuracy and repeatability of the IPAnema robot were performed. These lead to marginal improvements. An angular variation test which can be applied to any parallel machine is also introduced to evaluate the accuracy of the two kinematic models against each other.

Fig. 1
figure 1

IPAnema Winch showing the drum and cable guiding system. As the cable exits the winch it is passed through a pulley which also has a vertical hinge. This hinge allows the pulley to orientate towards the platform anchor point. In other words, the anchor point is always in the same plane as the pulley

2 Robot Architecture

The algorithms were tested on the cable robot IPAnema, constructed at the laboratories of the Fraunhofer IPA. Figure 2 shows the IPAnema cable robot, in the configuration during the experiment. The numbers indicate the winch positions, and the connecting cables are highlighted in red. In this exact configurations the dimensions (Table 1) were measured.

Fig. 2
figure 2

The Robot IPAnema pictured with the Leica LaserTracker

Table 1 Robot geometrical parameters: base vector \(\mathbf a _i\) and platform vector \(\mathbf b _i\)

The dimensions were determined very accurately using a Leica LaserTracker. With this optical device the absolute position of a reflector can be determined with an accuracy of \(\pm 15\,\upmu \text{ m} + 6\,\upmu \text{ m/m}\).

Fig. 3
figure 3

Standard kinematik description

3 Extended Kinematics for Cable Driven Robots

For reference, the basic kinematic algorithms are quickly introduced. On Fig. 3 the position of anchor points on the base and the robot platform are described by vector \(\mathbf a _{i}\) and \(\mathbf b _{i}\) respectively, and give the rope vector \(\mathbf l _i\) for a given pose. The platform vectors \(\mathbf b _{i}\) are in the coordinate system of the platform which is defined by the Cartesian vector \(\mathbf r \) and rotation matrix \(\mathbf R \). Since the length of the cables in the standard kinematic model is \(l_{i}=\Vert \mathbf l _{i}\Vert _{2}\) simple vector algebra yields

$$\begin{aligned} \mathbf a _i-\mathbf r -\mathbf R \mathbf b _i&= \mathbf l _i \end{aligned}$$
(1)
$$\begin{aligned} \Vert \mathbf a _i-\mathbf r -\mathbf R \mathbf b _i\Vert _{2}&= l_i \\ \mathrm for \,\, i=1,\ldots ,m.&\,&\nonumber \end{aligned}$$
(2)

This suffices for the general computation of inverse kinematics under the assumption that all cable connections are ideal points. This is also the basis for the standard forward kinematics used in [10]. Here, \(m\) functions

$$\begin{aligned} \varPsi _{i}\left(\mathbf l,r,R \right)= \left(\Vert \mathbf a _i-\mathbf r -\mathbf R \mathbf b _i\Vert _{2}\right)^2 -l^{2}_{i}\\\nonumber \mathrm for \,\,i=1,\dots ,m. \end{aligned}$$
(3)

are combined to give

$$\begin{aligned} \phi \left(\mathbf l \right)= \min _{\mathbf r,R }\sum _{i=0}^{m}\varPsi _{i}\left(\mathbf l,r,R \right), \end{aligned}$$
(4)

which will minimize \(\mathbf r,R \) for a given length vector \(\mathbf l =\left[l_1,\dots ,l_m\right]^T\). In very simple terms, this is almost equivalent to considering the pre-tensed cables as linear springs and minimizing their potential energy. Further factors such as cable stiffness need to be taken into account for this to truly apply, but in principle the approach would be almost identical.

To solve the forward kinematic problem, a Levenberg-Marquardt (LM) optimization algorithm is used which can be found in [5]. This solver minimizes the objective function \(\phi \left(\mathbf l \right)\) from (4) by iterative procedure

$$\begin{aligned} \left(\mathbf J (\mathbf l )\mathbf J ^T(\mathbf l )+\mu \mathbf I \right)\mathbf h =-\mathbf J ^T(\mathbf l )\phi (\mathbf l ). \end{aligned}$$
(5)

Where \(\mu \) is a damping parameter, \(\mathbf J (\mathbf l )\) is the Jacobian of \(\phi (\mathbf l )\) in dimension \(x,y,z\) and rotation angles \(a,b,c\)

$$\begin{aligned} \mathbf J (\mathbf l )= \displaystyle {\begin{bmatrix} \frac{\partial \varPsi _{1}}{\partial x}&\cdots&\frac{\partial \varPsi _{m}}{\partial x} \\ \frac{\partial \varPsi _{1}}{\partial y}&\cdots&\frac{\partial \varPsi _{m}}{\partial y} \\ \frac{\partial \varPsi _{1}}{\partial z}&\cdots&\frac{\partial \varPsi _{m}}{\partial z} \\ \frac{\partial \varPsi _{1}}{\partial a}&\cdots&\frac{\partial \varPsi _{m}}{\partial a} \\ \frac{\partial \varPsi _{1}}{\partial b}&\cdots&\frac{\partial \varPsi _{m}}{\partial b} \\ \frac{\partial \varPsi _{1}}{\partial c}&\cdots&\frac{\partial \varPsi _{m}}{\partial c} \\ \end{bmatrix}}^T \end{aligned}$$
(6)

and \(\mathbf h \) is each consecutive step. This does not guarantee a solution, but has shown good results in practice at very fast computational speeds. The lack of guaranteed solution is a severe impact on real-time capability. For this reason a maximum number of iteration steps (currently 100 steps) is implemented. This does not guarantee a solution, but ensures that there exists a guaranteed maximum computation time. In practice this maximum has not been reached, and the algorithm runs robustly in real time.

The extended kinematics takes into account of the pulley mechanism illustrated in Fig. 1. Where the equation for the length of cable \(i\) now reads

$$\begin{aligned} l_i=\theta _i r_p + l_{fi}. \end{aligned}$$
(7)

Here the angle \(\theta _i\) and the direct length from pulley exit point \(C_i\) to the platform anchor point \(\mathbf B _i\) are used to determine total cable length. \(\mathbf B _i\) is needed in the global coordinate frame simply

$$\begin{aligned} \mathbf B _i= \mathbf r +\mathbf R \mathbf b _i. \end{aligned}$$
(8)

There are many ways which can yield the parameters for (7) using basic trigonometry on the triangles formed by points: \(M_i\), \(B_i\), \(C_i\) and \(A_i\) (origin of coordinate system \(\mathcal K _A\) denoted by vector \(\mathbf a _i\)). The one derived in [11] is applied here.

This evaluation was used in the implementation of both forward and inverse kinematics, but deviates from the in [11] proposed method, in that it does not use transformation matrices to find the necessary lengths but only the vector \(\mathbf k _{Az}\) defined by the winch coordinate system. This is necessary to fulfill the real-time constraints, which need the equations to be evaluated as efficiently as possible. Eliminating evaluation of the angle of rotation of the pulley mechanism around axis \(k_{Az}\) and subsequent matrix evaluations is expected to give faster computations. This is done by evaluating the vector \(\mathbf m _i\) by

$$\begin{aligned} \mathbf m _i = \mathbf a _i+r_p{\hat{\mathbf w }} \end{aligned}$$
(9)

where \(\mathbf w \) is a vector from the origin of \(\mathcal K _A\) in the direction of \(M_i\) which is found by

$$\begin{aligned} \mathbf w = \left(\mathbf k _{Az} \times \left(\mathbf B _i-\mathbf a _i\right)\right)\times \mathbf k _{Az}. \end{aligned}$$
(10)

Hence

$$\begin{aligned} d_i = \Vert \mathbf B _i - \mathbf m _i \Vert _{2} \end{aligned}$$
(11)

and \(b_z\) is the distance from \(\mathbf m _i\) to \(\mathbf B _i\) along \(\mathbf k _{Az}\) given by

$$\begin{aligned} b_z=\Vert \mathbf k _{Az}\cdot \left(\mathbf B _i-\mathbf a _i\right)\Vert _{2} \end{aligned}$$
(12)

which helps to find

$$\begin{aligned} l_{fi}=\sqrt{r_p^2\times b_z^2} \end{aligned}$$
(13)

and finally

$$\begin{aligned} \theta _i = \arccos \frac{l_{fi}}{d_i}+\arccos \frac{b_z}{d_i}. \end{aligned}$$
(14)

This gives us all the dimensions needed to evaluate the inverse kinematics for each cable using Eq. (7).

As the same method is used for the forward kinematics, the extended forward kinematics simply replacing \(\Vert \mathbf a _i-\mathbf r -\mathbf R \mathbf b _i\Vert _{2}\) in Eq. (4) with the evaluation in Eq. (7) to give \(\tilde{\varPsi _i}\) which yields

$$\begin{aligned} \tilde{\phi } \left(\mathbf l \right)= \min _{\mathbf r,R }\sum _{i=0}^{m}\tilde{\varPsi _{i}}\left(\mathbf l,r,R,k _{Az},r_p\right). \end{aligned}$$
(15)

The initial guess for the LM optimizer is identical to the interval based method proposed in [10]. The full equation is implemented in the programming language c results in \(>\)50 lines of source code and the analytic Jacobian matrix \(>\)150, and is therefore not provided here (Fig. 4).

Fig. 4
figure 4

Kinematics of cable \(i\)

4 Validation

4.1 Computation and Convergence

To test real-time capability of this algorithm, it was first simulated on a desktop PC. This simulation used the geometric parameters measured for the accuracy evaluation, shown in Table 1.

The radius of the pulley was assumed to be identical for each winch and measured at \(r_p=21\) mm. The orientation of the winches can be seen in Fig.  and was assumed to be aligned perfectly with the axes. This means winches 1 and 5 were pointing in the negative x direction, winches 2 and 6 in the positive x direction, and winches 3, 4, 7, and 8 in the negative y direction.

For three different magnitudes of noise (0.1, 0.5 and 1 mm) the simulation was conducted for 5,000 positions chosen at random in the presumed workspace of the robot.

The continuous re-evaluation of the Eq. (15) through the LM solver poses the greatest risk for real-time capability of the algorithm. Depending on the number of iterations this can involve very many computations. Hence, the number of iterations of the LM solver is evaluated. Figure 5 shows the number of iterations for each simulated position. These are slightly worse than the results for the standard kinematics shown in [10], but are generally very reasonable, rarely exceeding 20 iterations, even for 1 mm noise. A few times the maximum number of iterations of 100 was reached, but these were most likely poses at the edge or beyond the workspace.

For this comparison it is important to note that convergence is very dependent on geometry and individual poses. Especially poses with big orientation differences are often at the edge of the workspace and will increase the number of necessary iterations.

Fig. 5
figure 5

Histograms showing number of iterations for forward kinematics optimizer. a Noise of 0.1 mm, b Noise of 0.5 mm, c Noise of 1 mm

Fig. 6
figure 6

Histograms showing number of iterations for forward kinematics optimizer. a Noise of 0.1 mm, b Noise of 0.5 mm, c Noise of 1 mm

The average position error of the platform shown in Fig. 6 was almost identical to that seen for the standard model, and is in the same order of magnitude as the noise error applied to the cables.

When using the analytically derived Jacobian matrix, the calculations times on a desktop pc ranged between 80 and 130 \(\upmu \text{ s}\) per evaluation. While this does not guarantee real-time capability, it is a good indication that this algorithm can be run in real-time. The test in practice proved successful, and so accuracy and repeatability measurements could be made. In fact, so far the algorithm running on the actual robot experienced no missed steps, when poses and trajectories of the robot were within the workspace.

4.2 Accuracy and Repeatability

The same LaserTracker used to determine the robot dimensions, was used to measure the accuracy and repeatability. Both kinematic models were tested in the exact same environment. Neither LaserTracker or the robot was moved, after the dimensions \(\left(\mathbf a _i,\mathbf b _i\right)\) were established. The reflector denoting the origin of both the global (at the platform home position) and the platform coordinate system was not altered throughout the experiment. This significantly increases the precision of the results as any systematic errors will be the same for both sets of data. Any calibrating of the LaserTracker would cause inaccuracies, as the measurement of reference points can add many forms of error to the calculations.

Accuracy and Repeatability were measured according to the ISO 9283 standard. Hence each pose was measured with 30 repetitions and through the same approach trajectory. The standard also defines testing conditions, which were adhered to. The calculations for the can be found in [6]. All poses had the same orientation of \(a=b=c=0\).

Table 2 Absolute positioning accuracy of standard and extended kinematics
Table 3 Repeatability of pose for standard and extended kinematics

As expected, the absolute accuracy was improved for the extended kinematic algorithm, but the repeatability stayed very much the same. Table 2 shows the results for the extended kinematic to be on average an improvement of roughly \(21\,\%\). Unfortunately this is lower than was hoped, and for some poses little to no improvement was seen. This indicates that other inaccuracies play an equally important role. The elasticity in the cables, or the inaccuracies in the drive chain of each winch would therefore provide an equal positioning error of the same magnitude \(\approx \)5 mm.

4.2.1 Angular Variation Test

Another test that was conducted was on the orientation accuracy. Since the platform origin was consistently measured, when the platform orientation is changed but the position \(x,y,z\) is not, this origin should not move. This concept is illustrated in Fig. 7 where the origin indicated by the thick dot is identical for four different orientations. This test can be implemented on any parallel kinematic machine, provided one can measure the origin about which the platform rotations are defined easily (Table 3).

Fig. 7
figure 7

Four orientations with the identical origin for the platform coordinate system at pose [0, 0, 1,000]

Thirty different orientations were tested with angles ranging in the ranges \(-5^\circ < a,b,c < 5^\circ \). Then the same calculations as for repeatability, as in the previous section, was used to evaluate the discrepancy in position between the different orientations. Table 4 shows that although there is a slight improvement for the extended kinematics, this is only 0.5 mm and therefore very marginal.

5 Conclusion

This paper presented the successful implementation of extended forward kinematics taking into account winch pulleys in a real-time system. In addition to providing the basic algorithm which can be implemented for any given robot structure provided it is theoretically overconstrained and has a reasonable workspace.

The algorithm is based on a LM optimizer which uses the Jacobian of objective function \(\phi ()\) the to determine a solution. The successful operation of the IPAnema robot with this extended kinematic proves the applicability, and real-time capability.

Table 4 Deviation in position at a change in orientation

Tests were conducted to investigate the improvement on accuracy through the use of extended kinematics. As expected absolute accuracy was improved while the relative accuracy remained similar. While there were measurable improvements, these were not as good as initially hoped. This means other imprecisions, inaccuracies, uncertainties in the robot have a similar impact, on the absolute accuracy, as the pulley mechanism. In addition a novel test was introduced and conducted to investigate orientational accuracy. This showed only marginal improvements when using extended kinematics.

To further improve the accuracy of the cable robot IPAnema, other factors need to be considered such as the elasticity of the cables. This can be the subject of ongoing research.