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

Comparing with rigid link-actuated manipulators, Cable-Driven Parallel Robot (CDPR) manipulators benefit from large workspaces, high speed motions and modular geometries. However, it appears that their control is a more complex issue as the cables must remain under tensions at any time [1]. To solve this issue, the proposed approaches in the literature can be classified in two main categories. In the off-line solutions, a path planning step is used prior to any motion in order to design a reference trajectory which guarantees that the cables will remain under tension during the predefined motion [2, 3], but assumes that a perfect control of the robot is available. In the on-line solutions, an algorithm of tension distribution (also known as redundancy resolution or force calculation) is used to maintain the cable tensions inside a predefined feasible workspace during the motion [4, 5]. This is a typical solution for redundant manipulators, where there are more cables than Degrees of Freedom (DoF) of the end-effector, and it is the solution considered in this work.

Concerning the position control of CDPR manipulators, most of the proposed methods rely on the joint position measurements. According to the coordinate space chosen to solve this control problem, there are two alternatives. In the first one, the controllers are designed in the joint space coordinates. Using the Inverse Position Kinematic Model (IPKM), the reference end-effector pose is converted in reference joint positions which are then controlled by a feedback loop. Some related works are the joint space PD controller proposed by Kawamura et al. applied to the SEGESTA robot [6] and later to the KNTU robot by Gholami et al. [7], and the joint space PID controller for the redundant suspended ReelAx8 prototype presented by Lamaury et al. [8]. In the second one, the controllers are designed in the task space coordinates. Assuming that the Direct Position Kinematic Model (DPKM) is available, the end-effector pose is calculated from the joint position measurements and a feedback control allows to track a reference pose. Gholami et al. evaluated such a task space PD controller and compared it to the previous approach [7]. However, for parallel manipulators, the direct kinematics is difficult to obtain (see for instance Carricato and Merlet for an intensive study on the matter [9]).

In the previously mentioned control schemes, the modelling errors and the deformations of the cables directly result in errors on the end-effector pose. One solution for improving the accuracy is then to use some exteroceptive sensors in order to obtain a direct measurement of the end-effector pose. Some preliminary works using cameras have been proposed by Dallej et al. for controlling the redundant suspended ReelAx8 robot [10] or the large-dimension CoGiRo robot [11].

The purpose of this paper is twofold. First, an original evaluation setup is introduced, based on an INCA 6D robot with eight cables developed by Haption, equipped with a motion-capture system Bonita developed by Vicon used for the measurement of the end-effector pose. Second, results from simulation and experiment are reported, based on an original control scheme relying on a cascaded control architecture in two parts. First is the position control to ensure an accurate end-effector positioning, which includes two nested closed-loops: an external vision-loop based on the pose measurement that drives the motors, equipped of inner speed-loop previously designed in order to control each speed in a decoupled fashion when rejecting the inherent non-linear behaviour of the cables. Second is the tension distribution to maintain the cables under feasible tensions, the paper makes an extensive review of the available methods and presents an algorithm inspired from one of them extended to the dynamic control.

The paper is organised as follows: Sect. 2 describes the setup (the INCA robot and the Bonita motion-capture system). In Sect. 3 the model of the robot is developed. In Sect. 4 the control strategies that are considered for evaluation are presented. The simulation and experiment results are presented in Sect. 5.

2 System Description

2.1 INCA Robot

The INCA robot [12] developed by Haption has a cubic configuration of 3 m by side, and uses eight driving cables to move the end-effector and eight balancing cables to ensure pretension in the driving cables when the motors are non-powered (Fig. 1b). Each actuator is placed on one of the eight vertices of the workspace (Fig. 1a) and is composed of a DC motor with a current-loop controller, which drives both the driving and balancing winches (Fig. 1b) to store, wind and unwind the cables.

A measurement of the motor positions and currents are respectively achieved by incremental optical encoders and current proprioceptive sensors.

Fig. 1
figure 1

The INCA robot a The INCA robot equipped with the 6 Bonita IR cameras. b Actuation scheme

2.2 Bonita Motion-Capture System

The Bonita motion-capture system used to measure the pose of the INCA end-effector is composed of six IR cameras (Fig. 1a) and a tracker software running on a Windows PC, all from the Vicon company. Each camera has its own emitting source and delivers a grayscale image with VGA resolution. Assuming that this stereo system has been previously calibrated, the pose of the INCA end-effector fitted with five retro-reflective fixed markers can be tracked by the software.

The temporal and spatial performances of the pose reconstruction are critical for the robot control and are evaluated:

  • the global latency of the system (delay between the start of the image acquisition and the availability of the pose measurement) is \(10.7\pm 0.7\) ms at a 200 Hz camera frame-rate. This latency of roughly twice the acquisition period is the sum of one period of image acquisition and one period for the pose reconstruction.

  • the accuracy of the pose is \(1.7\pm 0.4\) mm and evaluated by the RMS error in the IR images between the maker positions and their expected positions given by back-projection of the end-effector geometry with the reconstructed pose.

3 Modelling of the 6-DoF CDPRs

The model is derived from a generic model of the m-DoF CDPR manipulators with n cables, which is augmented with the pretension system (balancing cables, winches and springs) specific to the INCA prototype.

Given the size of the INCA robot and its cables of 1 mm diameter, the considered model assumes that the cables are of negligible mass (straight) and of infinite stiffness (inextensible). The model is briefly presented in this section, details can be found in [12].

3.1 Kinematics Modelling

To design the vision-loop control law, the Inverse Velocity Kinematic Model (IVKM) can be calculated by differentiating the Inverse Position Kinematic Model (IPKM) with respect to the time, and is given by the Jacobian matrix \( J_\theta \) that relates the end-effector velocity \( V_e = {[v_e^T \;\, w_e^T]}^T \) (including the linear \( v_e \) and angular \( w_e \) velocities) to the motor velocities vector \( \dot{\theta } = {[\dot{\theta }_1 \cdots \dot{\theta }_n]}^T \) such as:

$$\begin{aligned} \dot{\theta } = J_\theta (X_e) \; V_e \end{aligned}$$
(1)

where \( J_\theta \) can be easily calculated for parallel manipulators from the end-effector pose \( X_e = {[P_e^T \;\varPhi _e^T]}^T \) (including the position \( P_e \) and orientation \( \varPhi _e \)) as given in [12].

Considering the chosen representation of the orientation based on a system of three pure rotations Roll-Pitch-Yaw of angles \( \varPhi _e = {[\phi _r, \phi _p, \phi _y ]}^T \) respectively around the principal axes \( (X_o,Y_o,Z_o) \), the IVKM can be rewritten in terms of the time variation of the end-effector pose \( \dot{X}_e \) such as:

$$\begin{aligned} \dot{\theta } = J_\theta (X_e) \; J_\varPhi (\varPhi _e) \; \dot{X}_e \end{aligned}$$
(2)

where \( J_\varPhi (\varPhi _e) = \mathrm {blocdiag}\,(I_3, J_{rpy}(\varPhi _e)) \), in which the Jacobian \( J_{rpy} \) relates the angular velocity \( w_e \) to the speed of the chosen orientation \( \dot{\varPhi }_e \) as in [12]:

$$\begin{aligned} w_e = J_{rpy}(\varPhi _e) \, \dot{\varPhi }_e \end{aligned}$$
(3)

3.2 Dynamics Modelling

To determine the joint speed-loop control law, and for the purpose of simulations, a Direct Dynamic Model (DDM) has been developed. The DDM of the whole system projected in the task space coordinates can be written in the following form:

$$\begin{aligned} M(X_e) \; \ddot{X}_e + C(X_e, \dot{X}_e) \; \dot{X}_e + K(X_e) + G(X_e) = {F_e}_v \end{aligned}$$
(4)

under the following n constraints bounding the cable tensions vector \( T\, {=}\, {[T_1 \cdots T_n]}^T\):

$$\begin{aligned} T_{\min } \le T(I_m, \theta , \dot{\theta }, \ddot{\theta }) \le T_{\max } \end{aligned}$$
(5)

where the details of the inertia matrix M , the vector of forces and moments of Coriolis and centrifugal forces C , the vector of stiffness K and the vector of forces and moments of gravity G are given in [12]. The input vector of virtual wrenches \( {F_e}_v = {[{f_e}_v^T \; {m_e}_v^T]}^T \) meaning the external forces \( {f_e}_v \) and moments \( {m_e}_v \) acting on the end-effector resulting from the applied motor currents vector \( I_m = {[{I_m}_1 \ldots {I_m}_n]}^T \) is:

$$\begin{aligned} {F_e}_v = W_I(X_e) \, I_m \end{aligned}$$
(6)

with the wrench matrix \( W_I(X_e) = -J^T_\theta (X_e) \, K_{em} \), and the diagonal matrix of the motor torque constants \( K_{em} = \mathrm {diag}({k_{em}}_1, \ldots , {k_{em}}_n) \).

The cable tensions vector T can be estimated using the actuators dynamics by:

$$\begin{aligned} T(I_m, \theta , \dot{\theta }, \ddot{\theta }) = T_o + R_{pm}^{-1} \; [K_{em} \; I_m - J_{eq} \; \ddot{\theta } - {F_v}_{eq} \; \dot{\theta } - {F_s}_{eq} \; \mathrm {sign}({\dot{\theta }}) - K_{eq} \; \theta ] \end{aligned}$$
(7)

where the details of the diagonal matrices of driving winches radius \( R_{pm}\), equivalent inertia moment \( J_{eq} \), equivalent viscous \( {F_v}_{eq} \) and Coulomb \( {F_s}_{eq} \) friction coefficients, balancing springs equivalent rotational stiffness \( K_{eq} \), and the vector of initial cables pretension \( T_o \) are given in [12].

4 Kinematic Vision-Based Position Control

4.1 Overview

The cascaded control architecture considered here in Fig. 2 is implemented in two parts detailed later in this section:

  1. 1.

    The position control in itself, a kinematic position-based vision control (also known as Position-Based Visual Servoing (PBVS) or 3D Visual Servoing) which includes two nested closed-loops:

    • the external vision-loop in the task space coordinates aims to ensure an accurate end-effector positioning from the end-effector pose error.

    • the internal speed-loop in the joint speed coordinates aims to ensure a decoupled control of the motor speeds requested by the external loop while rejecting the inherent non-linear behaviour of the cables.

  2. 2.

    The tension distribution, that aims to maintain the cables under a tension that respects interval constraints.

Fig. 2
figure 2

Kinematic vision-based position control scheme with the tension distribution part

4.2 Position Control

4.2.1 Vision-Loop

For the system with measured pose \( X_e \) and controlled velocity \( v_e = \dot{X}_e \), an exponential convergence of the actual pose \( X_e \) towards the reference \( X^*_e \) is ensured by the proportional control law:

$$\begin{aligned} v^*_e = K \; (X^*_e - X_e) \end{aligned}$$
(8)

where the proportional gain matrix chosen under the shape \( K = \mathrm {blocdiag}(k_P \, I_3, k_\varPhi \, I_3) \) to tune the position and orientation, should be positive to adjust the response time of a stable control, and also diagonal to realise a decoupling between the position \( P_e \) and orientation \( \varPhi _e \) components of end-effector pose \( X_e \).

The vision-loop control signal \( \nu ^*_e \) being expressed in the task speed coordinates, is then converted into the joint speed coordinates \( \dot{\theta }^* \) using the IVKM (2).

4.2.2 Speed-Loop

The original proposed methodology relies on joint speed control. For the controller tuning, only one actuator control is considered, the others being considered as tension disturbances. The corresponding model is presented in Fig. 3, it includes a first-order model of the current-loop dynamics with the time constant \( \tau \), the motor torque constant \( k_{em} \) and a second-order model of the actuator dynamics represented by the inertia \( j_{eq} \), the viscous friction \( {f_v}_{eq} \) and the rotational stiffness \( k_{eq} \) due to the balancing spring. These parameters have been estimated experimentally in a previous work [12]. The cable tension T can be considered as a disturbance acting on the motor current control signal \( I^*_m \), and then should be rejected or compensated by the joint speed controller \( C_w \).

Fig. 3
figure 3

Speed-loop control scheme of one DC motor subject to the effects of its driving and balancing cables

A PI controller \( C_w(s) \) is generally sufficient for controlling the speed of a DC motor, the integral term being necessary in order to reject the disturbances:

$$\begin{aligned} C_w(s) = K_p \, \left( 1 + \frac{1}{T_i \, s}\right) \end{aligned}$$
(9)

It was tuned in order to reach a high bandwidth. Therefore, a design model was established by considering a high frequency approximation of the transfer from the motor torque \( \tau _m \) to the motor velocity \( \dot{\theta } \), resulting in the control model \( G_c(s) \) which suits to the controller design using the symmetrical optimum method (detailed in Sect. 5.2) for an efficient disturbances rejection [13]:

$$\begin{aligned} G_c(s) = \dfrac{k_{em}}{j_{eq} \, s \, (1 + \tau \, s)} \end{aligned}$$
(10)

4.3 Tension Distribution

4.3.1 State of the Art

In order to ensure that the vector of cable tensions T remains inside the feasible tensions workspace \( [T_{\min } \, T_{\max }] \), the speed-loop control signal of motor currents vector \( {I^*_m}_p \) leading to the virtual wrench \( {F_e}_v \) according to (6), is modified to solve the system of algebraic equations (6) under the inequality constraints (5). Due the robot redundancy, the system of equations (6) is under-determined and then has an infinity of solutions (assuming that \( W_I \) has full rank \( r = n - m \)) that can be determined by resolving the quadratic optimisation problem of the objective function E given by:

$$\begin{aligned} E = \dfrac{1}{2} \, \left( I^*_m - I_{obj}\right) ^T \, \left( I^*_m - I_{obj}\right) + \left( W_I \, \left( I^*_m - I^*_{mp}\right) \right) ^T \, \lambda \end{aligned}$$
(11)

where the variable objective currents vector \( I_{\mathrm {obj}} \) corresponding to an objective tensions vector \( T_{\mathrm {obj}} \), and the vector \( \lambda \in \mathbb {R}^m \) is the Lagrange multiplier associated to the equality constraints \( W_I \; (I^*_m - I^*_{mp}) = 0 \).

The set of solutions of (6) evolves in an r -dimensional subspace that can be written as following:

$$\begin{aligned} I^*_m = {I^*_m}_p + {I^*_m}_n \end{aligned}$$
(12)

where:

  • the particular solution \( {I^*_m}_p \) of minimum-norm aims to control the end-effector pose, and it is the previous PI speed-loop control signal.

  • the homogeneous solution \( {I^*_m}_n \) of \( W_I \) null-space aims to satisfy the tension constraints, while maintaining the end-effector on its actual pose:

    $$\begin{aligned} {I^*_m}_n = [I_n - W_I^+ \; W_I] \; I_{\mathrm {obj}} \end{aligned}$$
    (13)

Let us review the literature dedicated to the determination of the objective tensions vector \( T_{\mathrm {obj}} \) that maintains the cable tensions vector T within a feasible tensions workspace, ensuring the constraints (5). The available works can be classified in two categories. The first approach opted for iterative algorithms, so that efficient constrained optimisation methods can be used such as Linear Programming Methods (LPM) [1, 14], but the cable tensions continuity is not guaranteed. Other optimisation methods are also used such as Non-Linear Programming Methods (NLPM) in the particular case of Quadratic Programming Methods (QPM) [1, 15], and the general NLPM with the gradient descent method to resolve the problem in a quadratic formulation [7]. These quadratic methods guarantee the tensions continuity but have a non-predictable runtime. However, these algorithms are not suitable for the constraints of real-time control. Hence, the second approach relies on non-iterative algorithms to handle the real-time control constraints. For instance, Mikelsons et al. proved that the Center of Gravity (CoG) of the feasible tensions distribution workspace (the set of solutions of equations (6) satisfying the tension constraints (5)) is a solution that ensures the tensions continuity [16]. Recently, some other works have been proposed by Borgstrom [17], and by Lamaury and Gouttefarde which optimised the CoG method to the case of two degrees of redundancy [18].

4.3.2 Considered Algorithm

Unlike this previous second category of non-iterative algorithms with an evolutionary criterion, this work is inspired from an non-evolutionary algorithm proposed by Lafourcade [5] more appropriate to satisfy our real-time constraints (less than 1 ms), it is adapted to our case also considering a constant vector \( T_{\mathrm {obj}} \) but variable \( I_{\mathrm {obj}} \) due to the actuators dynamics of (7).

The proposed algorithm consists in: (1) selecting \( T_{\mathrm {obj}} \) inside the feasible tensions workspace and calculating \( I_{\mathrm {obj}} \) by inverting (7), (2) resolving the optimisation problem (11) without the tension inequalities constraints (5), (3) if some tension inequality constraints are violated then the q concerned inequalities selected among them are transformed into current equality constraints (not more than r tension inequality constraints can be saturated simultaneously) and included into the optimisation problem. All combinations of 1 to r violated tension inequality constrained are considered until one solution is met satisfying all the non-saturated tension inequalities constraints. If no solution is found, the vector \( I_{\mathrm {obj}} \) can be scaled by a scalar factor to not modify the trajectory and the process could be repeated. If the problem has no solution, the reference trajectory should be modified (not detailed herein).

When saturating a combination of q violated tension constraints, the control signal of motor currents vector \( I^*_m \) can be obtained by resolving the new quadratic optimisation problem of the objective function \( E_{\mathrm {sat}} \) given by:

$$\begin{aligned} E_{sat} = E + (S^T \; I^*_m - I_{\mathrm {sat}})^T \; \mu \end{aligned}$$
(14)

where the selection matrix \( S = [s_1 \ldots s_q] \in \mathbb {R}^{n \times q} \) concatenates the vectors \( s_k \) of the canonical basis of \( \mathbb {R}^n \) to select the combinations of the violated tension constraints to be saturated, and the vector \( \mu \in \mathbb {R}^q \) is the Lagrange multiplier associated to the current equality constraints \( S^T \; I^*_m - I_{\mathrm {sat}} = 0 \), such as the vector \( I_{\mathrm {sat}} \in \mathbb {R}^q \) is the currents vector that corresponds to the saturated tensions vector by inverting (7).

The set of solutions of the optimisation problem (14) can be written as:

$$\begin{aligned} I^*_m = {I^*_m}_p + {I^*_m}_t \end{aligned}$$
(15)

where:

$$\begin{aligned} {I^*_m}_t = {I^*_m}_n + \left[ W_I^+ \, W_I^{\mathrm {sat}} - S\right] \, [S^T \, W_I^+ W_I^{\mathrm {sat}} - I_q]^{-1} \, \Delta _{\mathrm {sat}} \end{aligned}$$

in which the resulting saturated wrench matrix is \( W_I^{\mathrm {sat}} = W_I \; S \), and the vector of the excessive motor currents \( \Delta _{\mathrm {sat}} = I_{\mathrm {sat}} - S^T \; ({I^*_{mp}} + {I^*_{mn}}) \) is the image of the excess in cable tensions evaluated by (7).

5 Results

5.1 Evaluation Task

In order to validate the vision-based position control scheme of Sect. 4, a set of end-effector trajectories are tested in simulation and experimentally. The end-effector being located on the measured initial pose \( {X_e}_o \), it is moved as follows:

  • Step trajectories: the end-effector reference trajectories are three pure translations of magnitudes \( {+}0.3 \) m, and rotations of angles \( {+}15^{\circ }\) along/around respectively \( X_o \), \( Y_o \) and \( Z_o \) axes.

  • Tracking trajectories: the end-effector reference trajectory is a circle belonging to the plane \( z = 0 \) m, located at the center of the workspace and of radius 0.3  m.

5.2 Controllers Design

This part details the design of the controllers used:

  • for the visual controller, the proportional gain matrix K is chosen as \( k_P = k_\varPhi = 6 \) rad\(^{-1}\) to get a time response of 500  ms on each component of the pose \( X_e \).

  • for the joint speed controller, the gains \( K_p \) and \( T_i \) are tuned using the symmetrical optimum method as follows:

    • first, the integration time constant \( T_i \) is chosen as \( T_i = a \, \tau \), where the coefficient a allows as to tune the phase margin \( \Delta \phi \) so that \( a = \tan ^2(\frac{\Delta \phi }{2} + \frac{\pi }{4}) \).

    • then, the proportional gain \( K_p \) is calculated as \( K_p = j_{eq} / (\tau \sqrt{a}) \), so that the phase margin corresponds to the maximal phase of the corrected system \( \phi _{\max } = \Delta \phi - \pi \), which occurs at the pulsation \( w_{\max } = 1 / (\tau \sqrt{a}) \).

    In our case, by selecting \( a = 20 \) (leading to \( \triangle \phi \simeq 65^{\circ } \)), we obtain: \( K_p = 0.1107 \) A\(\cdot \)s/rad and \( T_i = 26 \) ms. The achieved bandwidth for the joint speed control is 172  rad/s.

5.3 Obtained Performances

For the step trajectories, the time responses of each controlled component of the end-effector pose are given in Fig. 4 for the simulated and experimental cases. The response time is of 500 ms and the precision is less than 1  mm for the translations and less than \( 1^{\circ }\) for the rotations.

Fig. 4
figure 4

End-effector pose for the step trajectories. a Position along \(X_o\). b Orientation around \(X_o\)

The circular tracking trajectories of the end-effector are shown in Fig. 5 for the simulation and experimental cases. The corresponding time responses of the speed and current of the motor 1 are respectively given in the Figs. 6a and b.

Fig. 5
figure 5

End-effector pose for the circular tracking trajectory. a Spacial trajectory. b Temporal trajectory

Fig. 6
figure 6

Motor 1 responses for the circular tracking trajectory. a Motor 1 speed. b Motor 1 current

The results provided from the test trajectories clearly show that the reference signals are nicely tracked, with the previous response time and a very little error, showing a very close matching between the simulations and the experiments.

The feasible tensions workspace is defined by the boundaries \( T_{\min } = 1.48 \; \) N and \( T_{\max } = 18.52 \, \) N, which have been calculated based on the static model of the actuators, considering the current limits of the motors \( [0 \; 3] \) A, and the unwinding cable length limits \( [0 \; 4.82] \) m. The objective tension \( T_{\mathrm {obj}} \) has been dimensioned as \( T_{\mathrm {obj}} = 10 \; I_{8 \times 1} \) N. The objective current \( I_{\mathrm {obj}} \) is updated at each sample time using the dynamic model of the actuators from the objective tension \( T_{\mathrm {obj}} \). It can be seen on Fig. 7 that the eight cables are maintained under feasible tensions that are continuous during the circular motion of the end-effector.

Fig. 7
figure 7

Cable tensions for the circular tracking trajectory estimated using the actuators dynamics

6 Conclusion

This paper reports simulation and experiment results of the vision-based position control of a 6-DoF redundant CDPR INCA developed by Haption, equipped with the Bonita motion-capture system developed by Vicon to measure the end-effector pose. The control laws allow to track the pose reference trajectories with a response time of 500 ms and a precision less than 1  mm in translation and less than \( 1^{\circ } \) in rotation, while maintaining the cables under feasible tensions. The corresponding bandwidth of approximatively 6 Hz would allow to achieve pick-and-place tasks at a quite high pace. Deeper investigations will be necessary in order to evaluate the limitations of the control laws in terms of reachable bandwidth and robustness.