Keywords

1 Introduction

Cable-driven parallel mechanisms (CDPMs) have a proven track record in many different fields. Their architecture, allowing for large workspaces and relatively simple designs, has attracted much attention in the past two decades within academia and industry. This interest has resulted in multiple applications of CDPMs being developped, ranging from cable-driven cameras [4] to very large radio-telescopes [18], medical applications [17] and haptic devices [14]. Several researchers have also solved some of the computational problems associated with CDPMs. Related to the topic of this article, the problem of solving the direct kinematics of spatial fully constrained cable-driven parallel robots from six cable-length measurements alone has already been solved [9]. Indeed, it is equivalent to the problem of the direct kinematics of the Gough-Stewart platform. More recently, the problem of the forward displacement analysis of under-constrained CDPMs was also tackled [3]. The nature of this problem is not purely kinematic, however, as it also involves equilibrium conditions. To the knowledge of the authors, no workable, general, real-time solution has ever been reported to this problem.

In this paper, we propose to improve the accuracy of CDPMs by the addition of cable angular sensors. Already, assessing the accuracy of these mechanisms has been the scope of some research [5, 16]. Other researchers have proposed the use of additional length sensors for calibration purposes [15]. The strategic placement of angular sensors has also been discussed in [13], in order to solve the forward kinematics of CDPMs in closed-form. Previous studies on the implementation of cable angle sensors with the aim of improving accuracy have proposed a specific sensor design and a sensor fusion algorithm based on Kalman filtering [6].

The purpose of relying on additional angular sensor data for solving the forward kinematics is to increase the accuracy of the estimated CDPM pose, while also discriminating between different solutions. To do so, this paper proposes the use of the cable angle sensor first presented in [2, 12], and shown in Fig. 1. The advantages of using this particular sensor architecture are discussed in [6]. It should be pointed out, however, that the accuracy of such a device is in the order of \(1^{\circ }\). The main source of error is the two slots that allow the cable to freely change direction. These slots must be somewhat wider than the cable diameter to avoid impeding its motion, which results in small backlash. Notice also that past experience has shown that the semi-circular arms of a cable angle sensor can preserve the rectilinear shape of the cable, provided that it is under sufficient tension [6]. Indeed, the semi-circular arms, which are already light, are balanced about their respective rotation axes, so that their weight has no effect on the cable they guide. They are also mounted on ball bearings to minimise friction. Their effect on the shape of the cable can thus be made negligible, for most practical intents.

Fig. 1.
figure 1

Proposed angular sensor.

The structure of this paper is as follows. First, the geometric model of a generic planar CDPM is presented. Then, the forward kinematics with cable length measurement are briefly discussed, followed by the detailed resolution of the forward kinematics using cable angle measurement only. The proposed fusion method, using both cable length and angular position sensors, is then presented. Finally, an experiment is reported to compare the accuracy of the three different methods.

2 Geometric Model of a Planar Cable-Driven Parallel Robot

A cable-driven parallel robot consists of a mobile platform connected to reels on a fixed base by means of n cables acting in parallel. In the present case, a generic planar cable-driven parallel mechanism is considered. The geometric model of this mechanism is shown in Fig. 2. The position of the \(i^{th}\) anchor point \(B_{i}\) is defined by vector \(\mathbf {b}_{i}\) in the fixed reference frame, originating from O. The angle of the \(i^{th}\) cable with respect to the X axis in the fixed reference frame is defined by \(\theta _{i}\). The origin \(O'\) of the moving reference frame, which corresponds to the position of the end effector, is defined by vector \(\mathbf {t}=[x,y]^{\mathrm {T}}\) in the fixed reference frame. The orientation \(\phi \) of the end effector is defined by the rotation matrix \(\mathbf {Q}\). The point \(P'_{i}\) where the \(i^{th}\) cable is attached to the end effector, in the moving reference frame, is defined by vector \(\mathbf p _{i}'\) originating from \(O'\). Finally, it must be noted that the effects of cable mass and elasticity are not considered in this model.

Fig. 2.
figure 2

The geometric model of a generic planar cable-driven parallel mechanism

3 Forward Kinematics with Cable-Length Measurements

The classical approach to solving the forward kinematics for planar parallel mechanisms relies on the measurement of the cable lengths. The length of the \(i^{th}\) cable is given by the Euclidean norm of \(\varvec{\rho _{i}}\), the vector connecting \(B_{i}\) and \(P_{i}'\), which yields

$$\begin{aligned} ||\varvec{\rho _{i}}||_{2}=||\mathbf {t}+\mathbf {Q}\mathbf p '_{i}-\mathbf {b}_{i}||_{2},~i=1,2,\ldots , n. \end{aligned}$$
(1)

Computing (1) for each cable results in a nonlinear system of equations which must be solved to find the pose of the end effector. The analytical solution to this problem is known and results in a sixth order univariate polynomial [7, 8], where each real root of the polynomial corresponds to a different assembly mode of the mechanism.

4 Forward Kinematics with Cable Angle Measurements

Another approach to solving the forward kinematics of planar parallel mechanisms involves using cable angle measurements. In order to obtain such a measurement, a cable angle sensor capable of measuring the cable angles about two orthogonal axes has been proposed in [2, 12]. This section presents the forward kinematics solution by using the cable angles only, i.e., without any information on cable lengths. The loop closure equation for each cable is:

$$\begin{aligned} \mathbf {b}_{i}+\varvec{\rho }_{i}-\mathbf {Q}\mathbf p '_{i}-\mathbf {t}_{i}=\mathbf 0 ,~i=1,2,\ldots , n, \end{aligned}$$
(2)

where \(\varvec{\rho }_{i}=[\rho _{i}\cos \theta _{i},\rho _{i}\sin \theta _{i}]^{\mathrm {T}}\). Let us introduce a new rotation matrix:

$$\begin{aligned} \mathbf {\hat{Q}}_{i}=\begin{bmatrix} \cos (-\theta _{i})&-\sin (-\theta _{i}) \\ \sin (-\theta _{i})&\cos (-\theta _{i}) \end{bmatrix},~i=1,2,\ldots , n. \end{aligned}$$
(3)

We then multiply both sides of (2) by \(\hat{\mathbf {Q}}_{i}\). Geometrically speaking, this transformation results in vector \(\varvec{\rho }_{i}\) being parallel to the X axis of the fixed reference frame. Thus, the new equation can be written as a set of two scalar equations:

$$\begin{aligned} (-P'_{i,x}\cos \phi +P'_{i,y}\sin \phi&-x+B_{i,x})\cos \theta _{i} \nonumber \\&+(-P'_{i,x}\sin \phi -P'_{i,y}\cos \phi -y+B_{i,y})\sin \theta _{i}+\rho _{i}=0, \end{aligned}$$
(4a)
$$\begin{aligned} (B_{i,y}-P'_{i,x}\sin \phi -P'_{i,y}\cos \phi -&y)\cos \theta _{i}\nonumber \\&+(-B_{i,x}+P'_{i,x}\cos \phi -P'_{i,y}\sin \phi +x)\sin \theta _{i}=0, \end{aligned}$$
(4b)

where \(\rho _{i}\) is absent from (4b). Consequently, we discard (4a) and obtain a new system of n equations where we can write the unknowns as a vector x = \([x,y,\phi ]^{\mathrm {T}}\). When the robot uses more than three cables, the system of equations is overdetermined, since the number of unknowns is always three. In the present case, the proposed method for solving this system is the least squares method, which is a typical approach in this regard. Let us write the problem as

$$\begin{aligned} \mathrm {minimize}&~\frac{1}{2}\mathbf {f}^{\mathrm {T}}\mathbf {f}, \nonumber \\ \mathrm {over}&~\mathbf {x}, \end{aligned}$$
(5)

where \(\mathbf {f}\), the vector of residuals, is defined using Eq. (4b) as follows:

$$\begin{aligned} {\mathbf {f}}({\mathbf {x}})=\begin{bmatrix} (B_{1,y}-P'_{1,x}\sin \phi -P'_{1,y}\cos \phi -y)\cos (\theta _{1}) \\ +(-B_{1,x}+P'_{1x}\cos \phi -P'_{1,y}\sin \phi +x)\sin (\theta _{1})\\ \vdots \\ (B_{n,y}-P'_{n,x}\sin \phi -P'_{n,y}\cos \phi -y)\cos \theta _{n} \\ +(-B_{nx}+P'_{n,x}\cos \phi -P'_{n,y}\sin \phi +x)\sin \theta _{n} \end{bmatrix}. \end{aligned}$$
(6)

The condition for an extremum of \(\frac{1}{2}\mathbf {f}^{\mathrm {T}}\mathbf {f}\) is met when

$$\begin{aligned} \frac{\partial \frac{1}{2}\mathbf {f}^{\mathrm {T}}\mathbf {f}}{\partial {\mathbf {x}}}=0. \end{aligned}$$
(7)

Equation (7) represents a set of three equations in three unknowns: x, y and \(\phi \). These three equations being linear in x and y, a resultant equation containing only \(\phi \) can easily be obtained using a procedure such as the one used in [8]. The univariate resultant equation is then made algebraic by performing the tangent half-angle substitution: \(\sin \phi =2t/(1+t^2)\) and \(\cos \phi =(1-t^2)/(1+t^2)\). Clearing the denominators and any factor \((1+t^2)\) in the remaining expression leads to a polynomial of degree five in t. This polynomial is easily solved, and its only real root corresponds to the minimum sought. The optimum values of \(\phi \), x and y are obtained by back-substitution.

5 Sensor Fusion

In the previous sections, the forward kinematic problem was solved by using either cable lengths or cable angles. In this section, sensor fusion algorithms are proposed to extract the most accurate estimates from all the available information.

5.1 Three Loop-Closure-Equation Components

Having information on cable angles allows the use of the loop closure equations for solving the forward kinematics, instead of using the equations described in Sect. 3. Thus, the most straightforward method to solve the forward kinematic problem with both cable length and cable angle measurements consists in using the X and Y components of Eq. (2) for one cable, along with either the X or Y component of Eq. (2) for any other cable. This results in a system of three equations and three unknowns, which can be solved symbolically. However, while being fast and simple, this solution does not use the full potential of every sensor in the mechanism, which may result in non-negligible inaccuracies in the estimation of the pose of the effector.

5.2 Weighted Fusion by Propagation of Variance

Another method for solving the forward kinematics problem consists in solving the the loop closure equations in Eq. (2) for all n cables, all at once. This can be done via a simple least square approach, which even yields a symbolic solution. With this approach, however, the same weight is used for all sensors, even though their accuracies may differ, which is a significant drawback. Indeed, it is important to adjust the weight of each sensor measurement in the equations according to its rated accuracy. Therefore, this section presents the symbolic solution to the sensor fusion problem, where weights are introduced to better reflect the relative uncertainty between the two types of measurements.

Let us rewrite the loop-closure equations defined in Eq. (2), in scalar form:

$$\begin{aligned} B_{i,x}+\rho _{i}\cos \theta _{i}-\cos \phi {}P'_{i,x}+\sin \phi {}P'_{i,y}-x=0,~i=1,2,\ldots , n \end{aligned}$$
(8a)
$$\begin{aligned} B_{i,y}+\rho _{i}\sin \theta _{i}-\sin \phi {}P'_{i,x}-\cos \phi {}P'_{i,y}-y=0,~i=1,2,\ldots , n. \end{aligned}$$
(8b)

We then express \(\sin \phi \) and \(\cos \phi \) in terms of the half-angle tangent \(T=\tan (\phi /2)\), \(\phi =2\arctan (T)\), that is,

$$\begin{aligned} \sin (\phi )=\frac{2T}{1+T^{2}},\quad \cos (\phi )=\frac{1-T^{2}}{1+T^{2}}. \end{aligned}$$
(9)

Substituting (9) into (8a) and (8b) yields two quadratic polynomials in T:

$$\begin{aligned} B_{i,x}+\rho _{i}\cos \theta _{i}-P'_{i,x}-x+2P'_{i,y}T+(B_{i,x}+\rho _{i}\cos \theta _{i}+P'_{i,x}-x)T^{2}=0, \end{aligned}$$
(10a)
$$\begin{aligned} B_{i,y}+\rho _{i}\sin \theta _{i}-P'_{i,y}-y+2P'_{i,x}T+(B_{i,y}+\rho _{i}\sin \theta _{i}+P'_{i,y}-y)T^{2}=0. \end{aligned}$$
(10b)

We can then use (10a) and (10b) to define the residuals vector

$$\begin{aligned} \mathbf {f}=\begin{bmatrix} B_{i,x}+\rho _{i}\cos \theta _{i}-P'_{i,x}-x+2P'_{i,y}T+(B_{i,x}+\rho _{i}\cos \theta _{i}+P'_{i,x}-x)T^{2}\\ B_{i,y}+\rho _{i}\sin \theta _{i}-P'_{i,y}-y+2P'_{i,x}T+(B_{i,y}+\rho _{i}\sin \theta _{i}+P'_{i,y}-y)T^{2}\\ \vdots \\ B_{n,x}+\rho _{n}\cos \theta _{n}-P'_{n,x}-x+2P'_{n,y}T+(B_{n,x}+\rho _{n}\cos \theta _{n}+P'_{n,x}-x)T^{2}\\ B_{n,y}+\rho _{n}\sin \theta _{n}-P'_{n,y}-y+2P'_{n,x}T+(B_{n,y}+\rho _{n}\sin \theta _{n}+P'_{n,y}-y)T^{2}\\ \end{bmatrix} \end{aligned}$$
(11)

of a weighted least squares method

$$\begin{aligned} \mathrm {minimize}&~K=(1/2)\mathbf {f}^{\mathrm {T}}{\varvec{\Sigma }}^\mathrm {-1}_{\mathbf {f}}~\mathbf {f}, \nonumber \\ \mathrm {over}&~ \mathbf {x}. \end{aligned}$$
(12)

According to the Gauss-Markov theorem [11], the weight matrix value leading to the best linear unbiased estimator (BLUE) of \(\mathbf {x}\) is the inverse \({\varvec{\Sigma }}^\mathrm {-1}_{\mathbf {f}}\) of the variance-covariance matrix of \(\mathbf {f}\). In order to compute \({\varvec{\Sigma }}_\mathrm {\mathbf {f}}\), we apply the principle of the propagation of uncertainties. First, let \(\mathbf {z}\) be a vector containing the sensor values at any given time:

$$\begin{aligned} \mathbf {z}=[\theta _{1},\ldots ,\theta _{n},\rho _{1},\ldots ,\rho _{n}]^{\mathrm {T}}. \end{aligned}$$
(13)

Let us then express a linear approximation of \(\mathbf {f}\) at point \(\mathbf {z}\), using estimate \(\hat{\mathbf {z}}\), as:

$$\begin{aligned} \mathbf {f}(\mathbf {z})\approx \mathbf {f}(\hat{\mathbf {z}})+\left. \frac{\partial \mathbf {f}}{\partial \mathbf {z}}\right| _{\hat{\mathbf {z}}}(\mathbf {z}-\hat{\mathbf {z}}). \end{aligned}$$
(14)

Therefore, we can express \({\varvec{\Sigma }}_\mathrm {\mathbf {f}}\), the covariance matrix of \(\mathbf {f}\), as

$$\begin{aligned} {\varvec{\Sigma }}_\mathrm {\mathbf {f}}&= \mathrm {E}[(\mathbf {f}-\mathrm {E}[\mathbf {f}])(\mathbf {f}-\mathrm {E}[\mathbf {f}])^{\mathrm {T}}],\\ {\varvec{\Sigma }}_\mathrm {\mathbf {f}}&=\mathrm {E}\left[ \left. \frac{\partial \mathbf {f}}{\partial \mathbf {z}}\right| _{\hat{\mathbf {z}}}(\mathbf {z}-\mathrm {E}[\mathbf {z}])(\mathbf {z}-\mathrm {E}[\mathbf {z}])^{T}\big (\left. \frac{\partial \mathbf {f}}{\partial \mathbf {z}}\right| _{\hat{\mathbf {z}}}\big )^{\mathrm {T}}\right] , \\ {\varvec{\Sigma }}_\mathrm {\mathbf {f}}&=\left. \frac{\partial \mathbf {f}}{\partial \mathbf {z}}\right| _{\hat{\mathbf {z}}}{\varvec{\Sigma }}_\mathrm {\mathbf {z}}\big (\left. \frac{\partial \mathbf {f}}{\partial \mathbf {z}}\right| _{\hat{\mathbf {z}}}\big )^{\mathrm {T}}, \end{aligned}$$

where \({\varvec{\Sigma }}_\mathrm {\mathbf {z}}\) is the diagonal covariance matrix of \(\mathbf {z}\), and an upright E denotes the statistical expectation. The values of \({\varvec{\Sigma }}_\mathrm {\mathbf {z}}\) are determined from theory or from previous experience and must reflect the expected accuracy of each sensor. Tuning these parameters has an impact on the final solution, since it gives more or less weight to each corresponding sensor. Notice also that this expression of \({\varvec{\Sigma }}_\mathrm {\mathbf {f}}\) requires an estimate of the current pose of the effector. This rough estimate can simply be obtained with the method presented in Sect. 5.1 or with a non-weighted least squares method.

Computing the inverse of \({\varvec{\Sigma }}_\mathrm {\mathbf {f}}\) yields a symmetric block-diagonal matrix, namely,

$$\begin{aligned} {\varvec{\Sigma }}_\mathrm {\mathbf {f}}^{-1}=\begin{bmatrix} \mathbf {M}_{1}&0&\cdots&0 \\ 0&\mathbf {M}_{2}&\cdots&0 \\ \vdots&\vdots&\ddots&\vdots \\ 0&0&\cdots&\mathbf {M}_{n} \end{bmatrix},\quad \mathbf {M}_{i} \in \mathbb {R}^{2\times 2}. \end{aligned}$$
(15)

Thus, with the weight matrix derived, the objective function of (12) is now fully defined. The condition for an extremum of this function is met when

$$\begin{aligned} \frac{\partial K}{\partial {\mathbf {x}}}=0. \end{aligned}$$
(16)

Since the residual vector \(\mathbf {f}\) is post-multiplied by its transpose, and \({\varvec{\Sigma }}_\mathrm {\mathbf {f}}^{-1}\) is the inverse of a covariance matrix, which is positive semi-definite, the problem (12) is convex [1]. Consequently, any local minimum is also a global minimum, which means that only one real solution exists for this problem.

K being scalar and \({\mathbf {x}}=[x,y,T]^{\mathrm {T}}\) being the vector of unknowns, this results in a system of three equations and three unknowns. Computing Eq. (16), we see that the derivatives with respect to x and y can be written in compact form as a linear system of two equations:

$$\begin{aligned} (1+T^{2}) \begin{bmatrix} \alpha _{1,1}&\alpha _{2,1} \\ \alpha _{2,1}&\alpha _{2,2} \\ \end{bmatrix} \begin{bmatrix} x \\ y \\ \end{bmatrix} = \begin{bmatrix} \beta _{1,1}&\beta _{1,2}&\beta _{1,3} \\ \beta _{2,1}&\beta _{2,2}&\beta _{2,3} \\ \end{bmatrix} \begin{bmatrix} 1 \\ T \\ T^{2} \\ \end{bmatrix}. \end{aligned}$$
(17)

We can then solve this system for x and y, that is

$$\begin{aligned} \begin{bmatrix} x \\ y \\ \end{bmatrix} =\frac{1}{1+T^{2}} \begin{bmatrix} \alpha _{1,1}&\alpha _{2,1} \\ \alpha _{2,1}&\alpha _{2,2} \\ \end{bmatrix}^{-1} \begin{bmatrix} \beta _{1,1}&\beta _{1,2}&\beta _{1,3} \\ \beta _{2,1}&\beta _{2,2}&\beta _{2,3} \\ \end{bmatrix} \begin{bmatrix} 1 \\ T \\ T^{2} \\ \end{bmatrix} \end{aligned}$$
(18)

where the \(\alpha \) and \(\beta \) coefficients are constants. Substituting (18) in the remaining derivative in T yields, after simplification, a fifth order univariate polynomial in T:

$$\begin{aligned} \displaystyle \sum _{i=0}^{5} \gamma _{i}T^{i}=0 \end{aligned}$$
(19)

where the \(\gamma _{i}\) coefficients are functions of the sensor inputs, the weight matrix and the geometric parameters of the robot. Finally, finding the real root of Eq. (19) gives the value of T, which can then be substituted into Eqs. (18) and (9). Thus, the pose of the effector is fully defined.

Notice that the proposed algorithm is not iterative, except for the solution of Eq. (19), which is done using a standard eigenvalue algorithm. Although it is iterative, the computation of the eigenvalues of the \(6\times {}6\) companion matrix resulting from Eq. (19) can be done reliably in microseconds using currently available algorithms and computers. Let us also point out that the rest of the algorithm is performed in a predetermined number of operations, although it requires an initial guess of the pose, which is only used to estimate the covariance matrix \(\varvec{\Sigma }_{\mathbf {f}}^{-1}\).

The implementation of the algorithm in Matlab runs in 6 ms on a laptop computer equipped with an Intel Core i7-2640M running 2.8 GHz and with 8 GB of RAM. These computation times could be reduced even more by implementing the algorithm in a lower-level programming language such as C.

6 Simulated Example

In this section, a simulation is performed to validate the effectiveness of the propagation of variance fusion method. The robot geometry used for this simulation is presented in Fig. 3. For simplicity, a three-cable configuration was chosen, even though the methods presented in this paper can be applied to n cables.

Fig. 3.
figure 3

Robot configuration used for the experiment.

The simulation consists in comparing three sets of data corresponding to the end-effector pose, for given input parameters \(\theta _{i}\) and \(\rho _{i}\). The first data set is obtained by the forward kinematics solution using cable-length measurements only; The second data set is obtained from the forward kinematics using cable-angle measurements only; The third is obtained using a combination of both measurements through the sensor fusion algorithm described in Sect. 5.2. The exact values of the parameters are first obtained by specifying the desired arbitrary poses of the effector and computing the inverse kinematics of the robot. Random noise from a normal distribution of zero mean and arbitrary variance is then added to \(\theta _{i}\) and \(\rho _{i}\). In the present case, the variance corresponds to an uncertainty on cable-length measurements of the order of one centimetre, and of the order of one degree for angular measurement. Finally, the pose of the effector is obtained using these values.

Fig. 4.
figure 4

Estimated position \(\mathbf {t}\) of the effector for given \(\rho \) and \(\theta \) parameters with added noise. True position marked with a black cross. True orientation (not shown in this figure) is 0\(^\circ \). For the sensor fusion method, equal weights are given to \(\rho \) and \(\theta \) parameters. The number of samples per position is 150 per method.

Fig. 5.
figure 5

Estimated orientation \(\phi \) of the effector for given \(\rho \) and \(\theta \) parameters with uncertainties of \(\pm 1.5\) cm and \(\pm 1.15^\circ \) on cable length and angles respectively. True orientation is 0\(^\circ \) from vertical. The bounding sectors represent the maximum deviations in orientation for each position. For easier comparison, the error on the X,Y position is not shown. For the sensor fusion method, equal weights are given to \(\rho \) and \(\theta \) parameters.

Figure 4 presents the resulting distribution of effector position for each method. While the data points from these methods are generally distributed in different directions, the fusion results in a distribution that is tightly centred on the true position. This is particularly true near the edges of the workspace, where the estimates computed from a single type of measurement exhibit larger errors. This presents a clear advantage over, for example, computing a simple average of the cable length solution and the angular position solution, as the resulting data would spread away from the true position between the two distributions. Therefore, the results in Fig. 4 indicate that the pose obtained through sensor fusion is more accurate in terms of position than the other two methods.

Figure 5 presents the maximum deviation in effector orientation for different points in the workspace, with uncertainties of \(\pm 1.5\) cm and \(\pm 1.15^\circ \) on cable length and angle respectively. Similar conclusions can be drawn from this figure. We observe that the bounding sector is consistently more narrow for the data obtained through sensor fusion. In other words, the maximum deviation in effector orientation is always smaller with this method. Moreover, while the maximum deviation values vary greatly with position for the cable length solution and angular solution, they are generally constant when using sensor fusion.

Table 1 summarizes the data from Fig. 4. According to these results, when computing the position of the effector with the sensor fusion method, a 62% reduction in average RMS error is observed. In addition, the maximum error is even more significantly impacted, at 75% reduction versus using cable angle only and 68% reduction versus using cable length only.

Table 1. Error between calculated and true effector X,Y position. RMS value is first computed for each position, then averaged over the number of positions.

Table 2 presents the end effector orientation error. While Fig. 5 demonstrates that the maximum deviations are smaller with the sensor fusion method, we can conclude from this table that the average RMS error is also significantly lower. The data show a 61% reduction versus the cable length solution, and a 57% reduction versus the cable angle solution.

Table 2. Error between calculated and true effector orientation. RMS value is first computed for each position, then averaged over the number of positions.

7 Conclusion

In this paper, angular sensors are combined with cable-length measurements in order to improve the accuracy of planar CDPMs. A method for solving the forward kinematics of such a mechanism only from cable angles was first presented. The proposed sensor fusion algorithm, based on the loop-closure equations and a weighted least squares method, was then detailed. A simulation was finally performed to show the effectiveness of this algorithm.

The results indicate an improved accuracy in terms of end-effector position and orientation. Moreover, the precision of the proposed method is generally constant throughout the workspace. The method also presents the advantage of yielding a single solution, discriminating between multiple forward kinematics solutions, which is not the case with classical methods based on a single type of sensors.

Further work will consist in generalizing the proposed data fusion algorithm to CDPMs with six degrees of freedom. The robustness of the proposed method to the choice of the a priori estimate \(\hat{\mathbf {z}}\) could also be tested more extensively, since its effect on the final estimate of \(\mathbf {z}\) was not investigated.