Optimal Trajectory Planning of a Cable-Driven Parallel Robot by Direct Collocation Approaches
Subject Areas : robotics
Milad Badrikouhi
1
*
,
Mahdi Bamdad
2
1 - Mechanical and Mechatronics Engineering School, Shahrood University of Technology, Iran
2 - Mechanical engineering department, Shahrood university of technology
Keywords: B-Spline Interpolation Curves, Cable-Driven Parallel Robot, Direct Collocation, GPOPS-II, Trajectory Planning,
Abstract :
Trajectory planning in cable-driven robots is more challenging than rigid-link ones. To maintain the robot control, the cable tensions must be positive during motion. This paper presents a direct collocation approach to solve the optimal trajectory planning based on the minimization of a robot's tension and tension-rate objective functions. Besides, during robot motion, the cables must be tensile. The configuration of a cable parallel robot composed of a 3-cable and a prismatic actuator neutralizes the moving platform’s weight while improving tensionability. To generate smooth trajectories, the proposed method is compared with two standard approaches: GPOPS-II software package which uses Legendre-Gauss-Radu quadrature orthogonal collocation polynomials and direct collocation by using B-spline interpolation curves. Despite the efficiency of using B-spline functions in trajectory planning, numerical simulations demonstrate that the Hermite-Simpson direct collocation approach has a substantial benefit in the computation cost and accuracy for trajectory planning of a cable-driven parallel robot. Also, by choosing appropriate constraints and cost functions, the cable forces in the parallel robot can be well managed.
[1] Sohrabi, S., Mohammadi Daniali, H., and Fathi, A., Trajectory Path Planning of Cable Driven Parallel Manipulators, Considering Masses and Flexibility of The Cables, ADMT Journal, Vol. 9, No. 3, 2017, pp. 57-64.
[2] Shahabi, E., Hosseini, M., Kinematic Synthesis of a Novel Parallel Cable Robot as Artificial Leg, ADMT Journal, Vol. 9, No. 3, 2017, pp. 1-10.
[3] Hussein, H., Santos, J. C., and Gouttefarde, M., Geometric Optimization of a Large Scale Cdpr Operating on A Building Facade, In 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), 2018: IEEE, pp. 5117-5124.
[4] Phuoc Tho, T., Truong Thinh, N., Evaluating Cable Tension Distributions of CDPR for Virtual Reality Motion Simulator, Mechanics Based Design of Structures and Machines, 2023, pp. 1-19.
[5] H. D. Taghirad, Parallel Robots: Mechanics and Control, CRC press, 2013.
[6] Behzadipour, S., and Khajepour, A., Design of Reduced Dof Parallel Cable-Based Robots, Mechanism and Machine Theory, Vol. 39, No. 10, 2004, pp. 1051-1065.
[7] Zhao, X., Zi, B., and Qian, L., Design, Analysis, And Control of a Cable-Driven Parallel Platform with A Pneumatic Muscle Active Support, Robotica, Vol. 35, No. 4, 2017, pp. 744-765.
[8] Korayem, M. H., Bamdad, M., Tourajizadeh, H., Korayem, A. H., and Bayat, S., Analytical Design of Optimal Trajectory with Dynamic Load-Carrying Capacity for Cable-Suspended Manipulator, The International Journal of Advanced Manufacturing Technology, Vol. 60, No. 1, 2012, pp. 317-327.
[9] Badrikouhi, M., Bamdad, M., Novel Manipulability for Parallel Mechanisms with Prismatic-Revolute Actuators, GA-DP Trajectory Planning Application, Mechanics of Solids, Vol. 56, No. 2, 2021, pp. 278-291.
[10] Riyahi Vezvari, M., Nikoobin, A., Optimal Balancing of Spatial Suspended Cable Robot in Point-To-Point Motion Using Indirect Approach, ADMT Journal, Vol. 10, No. 3, 2017, pp. 87-96.
[11] Alibakhshi, R., Trajectory Optimization of Spherical Parallel Robots Using Artificial Neural Network, ADMT Journal, Vol. 7, No. 1, 2014.
[12] Betts, J. T., Survey of Numerical Methods for Trajectory Optimization, Journal of Guidance, Control, and Dynamics, Vol. 21, No. 2, 1998, pp. 193-207.
[13] Bamdad, M., Time-Energy Optimal Trajectory Planning of Cable-Suspended Manipulators, in Cable-Driven Parallel Robots: Springer, 2013, pp. 41-51.
[14] Hereid, A., Cousineau, E. A., Hubicki, C. M., and Ames, A. D., 3D Dynamic Walking with Underactuated Humanoid Robots: A Direct Collocation Framework for Optimizing Hybrid Zero Dynamics, in 2016 IEEE International Conference on Robotics and Automation (ICRA), 2016: IEEE, pp. 1447-1454.
[15] Kolathaya, S., Guffey, W., Sinnet, R. W., and Ames, A. D., Direct Collocation for Dynamic Behaviors with Nonprehensile Contacts: Application to Flipping Burgers, IEEE Robotics and Automation Letters, Vol. 3, No. 4, 2018, pp. 3677-3684.
[16] Patterson, M. A., and Rao, A. V., GPOPS-II: A MATLAB Software for Solving Multiple-Phase Optimal Control Problems Using Hp-Adaptive Gaussian Quadrature Collocation Methods and Sparse Nonlinear Programming, ACM Transactions on Mathematical Software (TOMS), Vol. 41, No. 1, 2014, pp. 1-37.
[17] Freeman, P., Minimum Jerk Trajectory Planning for Trajectory Constrained Redundant Robots, Washington University in St. Louis ProQuest Dissertations Publishing, 2012.
[18] Campbell, S., Kunkel, P., General Nonlinear Differential Algebraic Equations and Tracking Problems: A Robotics Example, Applications of Differential-Algebraic Equations: Examples and Benchmarks, 2018, pp. 1.
[19] Qian, S., Bao, K., Zi, B., and Zhu, W., Dynamic Trajectory Planning for A Three Degrees-of-Freedom Cable-Driven Parallel Robot Using Quintic B-Splines, Journal of Mechanical Design, Vol. 142, No. 7, 2020, pp. 073301.
[20] Li, Y., T. Huang, T., and Chetwynd, D. G., An Approach for Smooth Trajectory Planning of High-Speed Pick-and-Place Parallel Robots Using Quintic B-Splines, Mechanism and Machine Theory, Vol. 126, 2018, pp. 479-490.
[21] Santos, J. C., Chemori, A., and Gouttefarde, M., Redundancy Resolution Integrated Model Predictive Control of Cdprs: Concept, Implementation and Experiments, in 2020 IEEE International Conference on Robotics and Automation (ICRA), 2020: IEEE, pp. 3889-3895.
[22] Ueland, E., Sauder, T., and Skjetne, R., Optimal Force Allocation for Overconstrained Cable-Driven Parallel Robots: Continuously Differentiable Solutions with Assessment of Computational Efficiency, IEEE Transactions on Robotics, Vol. 37, No. 2, 2020, pp. 659-666.
[23] Dal Bianco, N., Bertolazzi, E., Biral, F., and Massaro, M., Comparison of Direct and Indirect Methods for Minimum Lap Time Optimal Control Problems, Vehicle System Dynamics, Vol. 57, No. 5, 2019, pp. 665-696.
[24] Rahaghi, M. I., Barat, F., Solving Nonlinear Optimal Path Tracking Problem Using a New Closed Loop Direct–Indirect Optimization Method: Application on Mechanical Manipulators, Robotica, Vol. 37, No. 1, 2019, pp. 39-61.
Int. J. Advanced Design and Manufacturing Technology, 2024, Vol. 17, No. 3, pp. 11-23
DOI: 10.30486/ADMT.2024.1104084 ISSN: 2252-0406 https://admt.isfahan.iau.ir
Optimal Trajectory Planning of a Cable-Driven Parallel Robot by Direct Collocation Approaches
Milad Badrikouhi *, Mahdi Bamdad
Mechanical and Mechatronics Engineering School,
Shahrood University of Technology, Iran
E-mail: badrykoohimilad@gmail.com, bamdad@shahroodut.ac.ir
*Corresponding author
Received: 29 February 2024, Revised: 9 June 2024, Accepted: 8 September 2024
Keywords: B-Spline Interpolation Curves, Cable-Driven Parallel Robot, Direct Collocation, GPOPS-II, Trajectory Planning
Biographical notes: Milad Badrikouhi received his BSc from Guilan University, (2008), MSc from the Iran University of Science and Technology, (2012), and PhD from Shahrood University of Technology, (2022) all in Mechanical Engineering. His research interests include robot dynamics and kinematics, design, and optimal control of serial and parallel robots. Mahdi Bamdad received his BSc, MSc, and PhD in Mechanical Engineering in 2004, 2006, and 2010, respectively. He is currently an associate professor at the Shahrood University of Technology (Iran). His research interests are in the areas of mechanisms design and optimization of robotic systems.
1 Introduction
In comparison with rigid links parallel robots, cable robots, have various profits such as low cost, low inertia, and friction, high payload-to-weight ratio, and large workspace toward serial robots[1-2]. Numerous Cable-Driven Parallel Robots (CDPRs) that have the benefit of this characteristic were constructed. The NIST RoboCrane, the SkyCam movable camera system, the flight simulator, and the virtual reality simulator are some of the CDPR applications [3-4]. However, the cables are flexible, and they can only bear the tension. Thus, n-DOF CDPR should have minimum n+1 cables to preserve the cable tension and manipulate the robot [5]. Similarly, for CDPRs that have n-DOF and n cables, instead of one more cable, another actuator can be used. As a remarkable example, a prismatic actuator was utilized to retain tension in all cables [6]. Also, a pneumatic muscle could play as the spinal cord rule in the design of biological cable robots to imitate the human neck [7]. In this work, the central spine is used to keep all cables in tension.
Optimal trajectory planning for the CDPR based on the definite cost functions provides a wide range of solutions [1], [8-11]. One of the best approaches to solving the problem of trajectory planning is optimal control theory. Two classes of direct and indirect approaches were considered for the optimal control problem (OCP) [12]. The indirect technique uses Pontryagin’s Minimum Principle. As an example, the time-energy optimal control problem for a CDPR with bounds on joint torques was solved by Bamdad [13].
Besides the indirect method’s advantages, it has a major defect due to falling in a local minimum. The boundary value problem is solved challenging since the results are sensitive to the unknown initial conditions [12]. Thus, in this paper, the direct approach is selected.
The direct method converts the trajectory planning to a parameter optimization problem. It uses discretizing the control and state variables. The key point about the direct method is that initial guesses have a low effect on the results. The integration process in the direct technique is essentially implicit. Compared to the indirect method, there is no need for analytical analysis and defining quasi-state variables. The key benefit of direct collocation is its directness. Also, the point and path constraints can be easily applied to the problem. Because of the discrete nature of the problem, there is no need for the shooting process, and high sensitivity to initial guess is removed. Thus, direct collocation is an influential nonlinear optimization technique that could be considered for systems with unstable dynamics and high nonlinearity. New research has established the potential of this approach [14-15]. In this article, an attempt is made to select a reliable direct method with minimum runtime to solve the trajectory optimization problem. On this basis, three direct methods of GPOPS-II, B-spline curves, and Hermit-Simpson collocation are compared with each other.
One of the direct approaches that convert the OCP to a discrete constrained minimization problem is the pseudo-spectral method. GPOPS-II uses the variable-order Gaussian quadrature methods as a standard software package [16]. In this technique, the state/control variables are approximated by interpolating polynomials, where the nodes are the roots of orthogonal polynomials. An example of GPOPS-II is minimum jerk trajectory tracking for redundant robots [17]. Also, Campbell and Kunkel attend to solve the unstructured tracking problem for a robot arm that has a flexible joint [18].
Also, trajectory planning has recently been mostly constructed by several interpolation functions such as polynomial, spline, and Bessel. Due to the main advantage of using spline curves on trajectory planning over polynomial and Bessel curves, several types of research based on B-spline curves could be found in prior literature. As an example, for a CDPR, a new pick-and-place solution by using the B-splines curves is presented in [19]. Also, acceleration and jerk optimization during trajectory have been found for parallel robots by B-spline curves in [20].
Mainly on the CDPR trajectory planning, because of the physical characteristics of cables, the special properties of cables must be considered. A minimum cable force limit is required to maintain all the cables in tension. Also, the maximum tension that cables can bear safely must be declared. In this regard, a model predictive controller is presented by Santos et al. which handles the tension distribution of the cables [21]. Also in [22], by optimal force allocation control, differentiable continuous tensions are guaranteed in over-constrained CDPR. In this work, the tension management of the cables is considered. Thus, the main contribution of this paper is:
1- A Hermite-Simpson fast-direct collocation method adapting to the dynamic model of a CDPR is introduced and employed to obtain the optimal trajectory in an off-line mode. For this purpose, also Gaussian quadrature by GPOPS-II and B-spline interpolation function which are well-known algorithms are selected to compare the numerical results and show the superiority of the Hermit-Simpson method.
2- Two practical cost functions are introduced regarding the management of cable tensions. The first scenario is the minimum tension trajectory planning and the second is the minimum tension rate. The problem constraints consist of tension limits so that the cables are always under control.
3- A hybrid CDPR consisting of a spine that exerts the normal force on the end-effector is offered. The normal force maintains all the cables tightened.
The remainder of this work is arranged as follows: Sections 2, 3, and 4 explain three well-known approaches of direct collocation scheme, Hermite-Simpson direct collocation, GPOPS-II, and using B-spline curves. Section 5 presents the CDPR, and the kinematics and dynamics are formulated. Section 6 signifies the problem statement. The dynamic Equation and the objective functions are considered. Minimum tension and minimum tension rate are selected as cost functions. The discretized dynamic Equation of motion is stated as the equality constraints and, the boundary conditions are expressed. Additionally, the cable forces must be maintained tensile during CDPR motion. In section 7, the dynamic model is verified by the ADAMS model. Section 8 discusses the simulation results of trajectory planning by three techniques, and ultimately, in section 9, the paper's conclusion is presented.
2 hermite-simpson direct collocation
The goal of CDPR trajectory planning is to generate the optimum controls according to the given objective function along with the physical limits such as maintaining positive cable tension. Thus, in a direct method, the CDPR state and controls are discretized. Commonly, the dynamic modeling of the CDPR is , where x ∈ Rn and u ∈ Rm designate the vector of states and controls. The problem is to find u(t), ∀t ∈ [0, T], such that a given objective function J is minimized:
Φ is the objective function, and h and g are formulated as the list of constraints [12]. This continuous system is converted to a discretized system with a finite number of variables by direct collocation. All approaches in direct methods divide the phase duration (time) into N -1 intervals, 0=t1<t2<…<tN=T where the points are denoted as a node. We use xk = x(tk). Let us indicate the control by uk = u(tk). Thus, a discrete-time dynamic is x (k+1) =f (x (k), u (k), k). We can collocate dynamic modeling via different approaches such as trapezoidal, Hermite-Simpson, etc. However, because of the adequate numerical accuracy, the Hermite-Simpson is applied for discretizing.
(2)
Where, h = (tN – t1) / (N -1) is the time between two nodes. Now, the optimal control problem converts to the optimization of an NLP problem. The optimization problem is defined in such a way that the state and control values, xk and uk are selected at each node in such a way that the dynamic Equations, boundary conditions, and all constraints are satisfied. In addition, the control values should be minimized according to the objective function simultaneously. The analytic Sequential quadratic programming, SQP solver is selected to solve this problem because it is faster and more precise rather than other algorithms, especially the evolutionary algorithm. In the optimization problem, selecting a reasonable initial guess can accelerate convergence and minimize the solution time. First, the optimization variables must be limited based on the physical nature of the joint variables and actuator forces. If it is considered yk=(xk,uk), it is supposed a lower bond lb and upper bound ub for each state and control variable yk as lb<yk<ub. In this paper, the linear initial guess between the boundary values of each state and control variable is considered in “Eq. (3)”.
Which yk0 is the initial guess. Also, y1 and yN are initial and final values.
3 GPOPS-II
GPOPS-II is a MATLAB package offered for solving OCPs for nonlinear dynamics. GPOPS-II utilizes a direct collocation technique by the pseudospectral functions [16]. The continuous-time OCP is approximated using a new class of variable-order Legendre-Gauss-Radau quadrature orthogonal collocation polynomials resulting in an NLP. As stated, GPOPS-II approximates both states and controls that translate the OCP into an NLP for each (K=1, 2, …, N-1) interval. The critical points of a solution by GPOPS-II are [23]:
· The algebraic constraints can be used.
· GPOPS-II can use automatic mesh refinement.
· To develop the required gradients, hessian and Jacobian, automatic differentiation is accessible.
B-spline curves are an interconnected set of Bezier curves in the following general form [12]:
(4)
The Equations of B-spline curves consist of two parts, basic functions Bi,k, and control points Ci. To calculate Bi,k, one must first determine the number of Bezier curves and their degrees. Then, the time should be divided by the number of curves. Each point is called a node thus the time node vector is formed t= [t1, t2, …, tN]. A value of time may be repetitive numerous times in a node vector, named the number of repetitions. The difference between the order of the curve, ki, and the number of repetitions mi determines the degree of smoothness si.
(5)
si designates the level of continuity in the node, which is equal to the si -1 order of derivation. By these assumptions, the basic functions can be calculated using the following relations:
(6)
The control points organize the curve and produce a continuous concept. B-spline curves behave quite locally. By changing one of the control points, only the shape of the curve in the vicinity of the control point changes and the rest of the B-spline curve remains unchanged.
5 CDPR Modeling
A prismatic central linkage is used in this CDPR to supply structural stability. This central spine with wire actuation is utilized to obtain various important benefits while the advantages of a CDPR are needed. In “Fig. 1”, the CDPR CAD model is illustrated. This platform has 3-DOF: pitch, roll, and heave. In this mechanism, the cylinder is fixed at point O to the base and attached to the EE at point Pm by a 2-DOF Cardan joint. Universal joint limits the platform’s rotation about the Z-axis as a single rotational DOF. Two other movements, moving forward/backward and moving left/right are also prevented.
|
Fig. 1 CDPR CAD model.
A prismatic actuator is used to eliminate the gravitational effects for any CDPR configuration. Thus, it makes the potential energy constant. The use of a prismatic joint has some advantages. The prismatic actuator supports the end-effector’s weight while improving the tensionability condition. Positive tension must be guaranteed during CDPR motion. The cylinder moves the moving platform up and down, and the cables are designed to direct the EE. Since the pneumatic cylinder tolerates the EE weight, to guide the EE, using powerful motors is not necessary.
For kinematic analysis, the reference frame [A: XYZ] is fixed at point O to the base, and the moving frame [B: xyz] is attached to the EE at point Pm, the EE center of mass. The EE coordinate x is expressed in [z, α, β] T. z denotes the height of the Pm, α denotes the EE pitch angle around the X-axis, and β denotes the EE roll angle around the Y-axis. In inverse kinematics, these coordinates are considered. The q = [l1, l2, l3, d] T is the joint coordinate. li is the cable length, and d is the cylinder position. Since the pneumatic cylinder is fixed to the base, z = d+d0, in which the fixed length of the pneumatic cylinder d0 is considered 0.5m. The angle between the right-hand side of the X-axis and OSi is θi (i=1,2,3). The schematic diagram of the mechanism is introduced in “Fig. 2”. To obtain the cable length, we form the following Equations:
(7)
OSi is a constant vector. Also, OPi = z + PmPi, in which z is known. For PmPi, we have PmPi =RmoPi. Rmo =RPR=Ry(β)Rx(α) is the rotation matrix of the EE. Also, Pi is the primary position of the vector PmPi relative to the frame [B]. Consequently, the inverse kinematic Equation is:
(8)
Fig. 2 CDPR kinematic and FBD diagram.
By velocity loop closure, the Jacobian is calculated. I, J, K is the unit vector of a frame [A], and i, j, k is the unit vector of [B]. The relationship between the joint velocities and EE velocity is explained in the following Equation:
In which Jx is the Jacobian, is the velocity vector of the joints, and
is the EE velocity. First, we notice the next Equation, which is established in every closure loop of the parallel platform.
(10)
In the next step, we differentiate from each term of Eq. (10). First, by considering prismatic joint, dOPm/dt= with pitch–roll rotation, we have:
Also, OSi is a constant vector. As a result, dOSi/dt=0. Also, li direction through a unit vector si is calculated as follows:
(12)
The angular velocity vector of the cables, Ωli is perpendicular to si, and cables do not rotate around themselves, as a result:
Therefore, the final Equation for velocity loop closure is rewritten as:
(11)
For calculating Jx, the cross product of the vector si satisfies the following Equation.
Considering PmPi = Ei, “Eq. (12)” simplifies to:
Rewriting “Eq. (13)” results in:
From “Eq. (5)”, , using “Eq. (14)” for i = 1, 2, 3, Jx is derived as:
(15)
The manipulator dynamic Equation of motion can be obtained from the Newton-Euler formulation. In this case, the cable mass and friction are neglected. Let Wenv = [Fz, Tx, Ty] T be the wrench applied on the EE center by the environment and τ=[T1, T2, T3, Fz] T is the actuator force where Ti is the tensions and Fzc is the cylinder force. The EE position/orientation relative to the world coordinate systems is denoted by three variables in x=[z, α, β] T. After CDPR Jacobian Jx calculated from “Eq. (11)”, nonlinear differential Equations of motion for the CDPR is rewritten as:
In which D(x) signifies the CDPR mass matrix, signifies the Coriolis and centrifugal matrix, and G(x) signifies the gravity effect, all will be presented in Appendix A. The CDPR Jacobian Jx is calculated from “Eq. (15)”. As a result, the state space can be developed as below:
(17)
6 Problem statement
Due to trajectory planning, the direct collocation method should be adapted with CDPR modeling. First, from the dynamics, the states are the joint position and velocity, and the controls are the actuator. Thus, the optimization variables are:
In which k = 1, 2, …, N. The NLP variables that should be optimized based on the cost function are y= (y1, y2, …, yN)T. The trajectory planning problem is to detect y in all nodes considering boundary conditions and constraints. This problem is prescribed with cable force and force rate in the objective functions. The inequality constraints include positive force in the cables. “Table 1” explains the objective function. From “Eq. (17)” and using “Eq. (3)”, the dynamic constraint is established as the equality constraint: Minimize J
Table 1 Cost functions definition
Cost functions | Continuous form | |
Minimum– tension |
| |
Minimum – tension–rate |
|
Subject to: |
|
(19)
The boundary conditions are the second list of constraints.
For cable constraints, it must be considered positive tension otherwise, the CDPR performance will be troubled.
(21)
At time tk, Fik= Fi(tk) represents the tension (i=1,2,3). Fallow is the minimum cable force and is 10N. The CDPR parameters are denoted in “Table 2”. SQP by the suggested procedure in “Fig. 3” solves this trajectory planning problem.
Table 2 The cable robot parameters
Value | Unit | ||
Angle | θ1 =0 θ2 =120 θ3 =240 | degree | |
Base radius | rb =0.8 | m | |
EE radius | re =0.2 | m | |
EE mass | m=100 | Kg | |
EE moment of inertia | I=1 | Kg.m2 | |
Initial time | t1 =0 | s | |
Final time | tN =2 | s |
Algorithm Direct collocation trajectory planning of a CDPR |
Input: 1: Get the parameters: θi, rb, re, m, I, t1, tN. 2: Define lower bond lb and upper bond ub. 3: Define the boundary values by Eq. (20). 4: Define the linear initial guess matrix 5: Consider the NLP variables y= Constraint function. 6: For k=1 to N -1 do 7: Consider dynamics constraints (“Eq. (19)”). 8: End for 9: Set the boundary conditions (“Eq. (20)”) and positive tensions (“Eq. (21)”). Objective function. 10: For k=1 to N -1 do 11: Define the objective function (“Table 1”). 12: End for Direct collocation method: 13: While the optimality condition is satisfied do 14: Call the Objective function and Constraint function. 15: Compute new trajectory y by NLP iterative search algorithm. 16: End while Output: 17: Report optimal trajectory ys = y. |
Fig. 3 The proposed algorithm.
7 Dynamic model verification
To verify the dynamic modeling, a model is implemented through ADAMS software. As shown in “Fig. 4”, this model includes complete details of the CDPR. To verify, nonlinear actuator controls are considered.
(22)
Fig. 4 ADAMS model.
The simulation results of both methods are quite similar. The model simplification causes small inaccuracies between the MATLAB and ADAMS models. It is considered the ideal universal joint in MATLAB. Thus, the EE gravitational force has no torque around the center of the U-joint, but in ADAMS there is. Also, in the MATLAB model, it is considered that the moving platform has no thickness. Some minor errors may be caused by the numerical errors of the ordinary differential Equation solver in ADAMS, which are reasonable in a sense. Therefore, the accuracy of the dynamic model is verified (“Fig. 5”).
(a)
(b)
(c)
Fig. 5 Results of the MATLAB and ADAMS simulation: (a): EE center of mass z position, (b): roll angle, and (c): pitch angle.
8 trajectory planning with hermite-simpson, GPOPS-II, and B-spline curves methods
For simulation, the computer specification is Windows 7 Pro, Intel (R) Core (TM) i5 CPU M-480 @ 2.67GHz and 4GB RAM. MATLAB has been used for simulation. We can compare GPOPS-II, Hermite-Simpson, and B-spline methods corresponding to the minimization of the cost function. Solving the trajectory planning problem by minimizing tension and tension rate is summarized in “Table 3”. The runtime is divided into ten nodes.
Also, three stopping criteria for SQP solver are defined. Generally, the stopping criteria are thresholds that, if crossed, stop the iterations. TolX is the minimum size of a step. If the solver takes a step tinier than TolX, the iterations finish. TolFun is a minimum change in the cost function value during a step. The process will be completed when |J (xk) – J (xk+1)| < TolFun. At last, MaxIter is the number of solver iterations. If the number of iterations exceeds the MaxIter, the simulation is ended. The stopping criteria for the three methods are considered the same, TolX = TolFun = 10-3, and MaxIter = 30000. First, solving the trajectory planning problem through minimizing tension is considered. The results for direct collocation, GPOPS-II, and B-spline are illustrated in “Fig. 6”.
(a)
(b)
(c)
(d)
(e)
(f)
(g)
Fig. 6 Results through minimizing cable’s tension.
Table 3 Results for the minimum-tension cost function
Methods | Runtime (s) | Cost function value |
Hermite-Simpson | 0.86 | 399 |
GPOPS-II | 10.31 | 385 |
B-spline | 7.73 | 427 |
The results show that Hermit-Simpson's method is superior to other methods in terms of problem-solving time. Also, in the GPOPS-II method, there are drastic changes in increasing or decreasing the force of the pneumatic cylinder, which is not desirable at all. Therefore, as two reliable methods, the results related to the Hermit-Simpson method and B-splines function are proposed. From the viewpoint of the cost function, the results of the Hermit-Simpson method are superior to the B-spline technique. It can also be seen that the changes related to the cable forces in terms of time are less in the case of the B-spline method, and smoother forces have been obtained. Second, the problem is considered by minimizing the tension rate of the cables. The results are shown in “Fig. 7”.
(a)
(b)
(c)
(d)
(e)
(f)
(g)
Fig. 7 Results through minimizing cable’s tension rate.
The results show that the B-Spline method is the most time-consuming in terms of runtime. In the GPOPS-II method, there are severe changes in the tension of the cables and the pneumatic cylinder force, which proves that this method is not desirable for meeting the control demands. It is clear from the value of the objective function in “Table 4” that this method could not minimize the value of the cost function. From the viewpoint of minimizing the objective function, the results of the Hermite-Simpson method are significantly superior to the B-spline method.
Table 4 Results for the minimum-tension-rate cost function.
Methods | runtime (s) | Cost function value |
Hermite-Simpson | 1.16 | 0.95 |
GPOPS-II | 1.08 | 272640 |
B-spline | 7.11 | 10.61 |
Finally, the cable tensions obtained from two objective functions, minimum-tension and minimum-tension-rate by Hermit-Simpson direct collocation are compared in “Fig. 8”.
(a)
(b)
(c)
Fig. 8 Comparing results through minimizing cable’s tension and cable’s tension-rate.
From “Table 5” and “Fig. 8”, it can be seen that if the designer wants the changes in cable forces to be minimal, the function of minimum-tension-rate can be used. However, using this function increases the amount of cable forces. Otherwise, the forces obtained from the simulation with the objective function of minimum-tension give acceptable results.
Table 5 Results of the Hermit-Simpson direct collocation for the minimum-tension (J1) and minimum-tension-rate (J2) objective function
Cost function selection | J1 | J2 |
J1 J2 | 399 | 105 |
2123 | 0.95 |
9 CONCLUSIONS
The development of optimal trajectory planning algorithms is a main issue in efficiently performing cable-driven parallel robot tasks. Direct collocation schemes are considered in this paper to solve the trajectory planning problem for CDPRs. First, the optimization problem and direct schemes were introduced. Then the CDPR kinematics and dynamics are obtained. Next, the problem statement of the trajectory planning is expressed in detail. The trajectory planning's key emphasis was on the cable tensions in the cable robot with the prismatic actuator considering the boundary conditions and positive cable tension constraints. Before the trajectory planning, the MATLAB model is verified by an ADAMS model. The two models have a good agreement in the results of motion parameters to the nonlinear input forces and thus, the CDPR dynamics is correct (“Fig. 5”). Direct collocation approaches in trajectory planning including Hermite-Simpson, GPOPS-II, and B-spline method are compared in “Tables 3 and 4”. The results from the minimum-tension objective function from “Table 3 and Fig. 6” in this simulation show that using the Hermite-Simpson and B-spline methods has good performance in minimizing the cost function rather than GPOPS-II. But the Hermite-Simpson is the most accurate and fast among the methods. The results obtained from the minimum-tension-rate objective function from “Table 4 and Fig. 7” show that GPOPS-II is not desirable in satisfying the control demands and could not minimize the value of the objective function. Also, the Hermite-Simpson has a better performance and less runtime rather than B-spline. Thus, this shows that the Hermite-Simpson direct collocation technique is an appropriate method for this trajectory planning problem. Furthermore, this technique can be simply formulated and proposed for other case studies. Also, by comparing the cable tensions in “Table 5 and Fig. 8”, the role of cost functions in cable tension management is determined. In the case where minimum-tension-rate is used, the changes in tensions will be less, but the value of cable tensions and consequently the energy consumed is more. As in research [14] and [15], the use of the direct collocation method has brought reliable results. In various research, indirect methods [8], polynomial and harmonic functions [24], and other basic functions have been used for trajectory planning. This issue may be directly related to the unfamiliarity of the direct collocation method. Also, due to the existence of ready toolboxes such as GPOPS-II and default MATLAB software commands, researchers have usually used these toolboxes and commands or previously known methods. Apparently, there are some limitations in this research. In dynamic modeling, the ideal universal joint is considered. Also, friction between the CDPR elements, cable mass, and the moving platform thickness are neglected. But despite this, the presented model has a good match with the Adams model. On the other hand, the mathematical complexities of modeling have been avoided. Also, due to the time limit, three direct methods were compared in solving the trajectory optimization problem, and in future research, other methods can be used in solving the trajectory planning problem.
10 Appendix or Nomenclature
Ei is the vector from the EE center to the attachment point of the cables after pitch-roll rotation. Hence:
In which RPR is the pitch-roll rotation matrix. is calculated as:
Hence, is obtained as follows:
Also, the elements of “Eq. (16)” are presented as follows:
References
[1] Sohrabi, S., Mohammadi Daniali, H., and Fathi, A., Trajectory Path Planning of Cable Driven Parallel Manipulators, Considering Masses and Flexibility of The Cables, ADMT Journal, Vol. 9, No. 3, 2017, pp. 57-64.
[2] Shahabi, E., Hosseini, M., Kinematic Synthesis of a Novel Parallel Cable Robot as Artificial Leg, ADMT Journal, Vol. 9, No. 3, 2017, pp. 1-10.
[3] Hussein, H., Santos, J. C., and Gouttefarde, M., Geometric Optimization of a Large Scale Cdpr Operating on A Building Facade, In 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), 2018: IEEE, pp. 5117-5124.
[4] Phuoc Tho, T., Truong Thinh, N., Evaluating Cable Tension Distributions of CDPR for Virtual Reality Motion Simulator, Mechanics Based Design of Structures and Machines, 2023, pp. 1-19.
[5] H. D. Taghirad, Parallel Robots: Mechanics and Control, CRC press, 2013.
[6] Behzadipour, S., and Khajepour, A., Design of Reduced Dof Parallel Cable-Based Robots, Mechanism and Machine Theory, Vol. 39, No. 10, 2004, pp. 1051-1065.
[7] Zhao, X., Zi, B., and Qian, L., Design, Analysis, And Control of a Cable-Driven Parallel Platform with A Pneumatic Muscle Active Support, Robotica, Vol. 35, No. 4, 2017, pp. 744-765.
[8] Korayem, M. H., Bamdad, M., Tourajizadeh, H., Korayem, A. H., and Bayat, S., Analytical Design of Optimal Trajectory with Dynamic Load-Carrying Capacity for Cable-Suspended Manipulator, The International Journal of Advanced Manufacturing Technology, Vol. 60, No. 1, 2012, pp. 317-327.
[9] Badrikouhi, M., Bamdad, M., Novel Manipulability for Parallel Mechanisms with Prismatic-Revolute Actuators, GA-DP Trajectory Planning Application, Mechanics of Solids, Vol. 56, No. 2, 2021, pp. 278-291.
[10] Riyahi Vezvari, M., Nikoobin, A., Optimal Balancing of Spatial Suspended Cable Robot in Point-To-Point Motion Using Indirect Approach, ADMT Journal, Vol. 10, No. 3, 2017, pp. 87-96.
[11] Alibakhshi, R., Trajectory Optimization of Spherical Parallel Robots Using Artificial Neural Network, ADMT Journal, Vol. 7, No. 1, 2014.
[12] Betts, J. T., Survey of Numerical Methods for Trajectory Optimization, Journal of Guidance, Control, and Dynamics, Vol. 21, No. 2, 1998, pp. 193-207.
[13] Bamdad, M., Time-Energy Optimal Trajectory Planning of Cable-Suspended Manipulators, in Cable-Driven Parallel Robots: Springer, 2013, pp. 41-51.
[14] Hereid, A., Cousineau, E. A., Hubicki, C. M., and Ames, A. D., 3D Dynamic Walking with Underactuated Humanoid Robots: A Direct Collocation Framework for Optimizing Hybrid Zero Dynamics, in 2016 IEEE International Conference on Robotics and Automation (ICRA), 2016: IEEE, pp. 1447-1454.
[15] Kolathaya, S., Guffey, W., Sinnet, R. W., and Ames, A. D., Direct Collocation for Dynamic Behaviors with Nonprehensile Contacts: Application to Flipping Burgers, IEEE Robotics and Automation Letters, Vol. 3, No. 4, 2018, pp. 3677-3684.
[16] Patterson, M. A., and Rao, A. V., GPOPS-II: A MATLAB Software for Solving Multiple-Phase Optimal Control Problems Using Hp-Adaptive Gaussian Quadrature Collocation Methods and Sparse Nonlinear Programming, ACM Transactions on Mathematical Software (TOMS), Vol. 41, No. 1, 2014, pp. 1-37.
[17] Freeman, P., Minimum Jerk Trajectory Planning for Trajectory Constrained Redundant Robots, Washington University in St. Louis ProQuest Dissertations Publishing, 2012.
[18] Campbell, S., Kunkel, P., General Nonlinear Differential Algebraic Equations and Tracking Problems: A Robotics Example, Applications of Differential-Algebraic Equations: Examples and Benchmarks, 2018, pp. 1.
[19] Qian, S., Bao, K., Zi, B., and Zhu, W., Dynamic Trajectory Planning for A Three Degrees-of-Freedom Cable-Driven Parallel Robot Using Quintic B-Splines, Journal of Mechanical Design, Vol. 142, No. 7, 2020, pp. 073301.
[20] Li, Y., T. Huang, T., and Chetwynd, D. G., An Approach for Smooth Trajectory Planning of High-Speed Pick-and-Place Parallel Robots Using Quintic B-Splines, Mechanism and Machine Theory, Vol. 126, 2018, pp. 479-490.
[21] Santos, J. C., Chemori, A., and Gouttefarde, M., Redundancy Resolution Integrated Model Predictive Control of Cdprs: Concept, Implementation and Experiments, in 2020 IEEE International Conference on Robotics and Automation (ICRA), 2020: IEEE, pp. 3889-3895.
[22] Ueland, E., Sauder, T., and Skjetne, R., Optimal Force Allocation for Overconstrained Cable-Driven Parallel Robots: Continuously Differentiable Solutions with Assessment of Computational Efficiency, IEEE Transactions on Robotics, Vol. 37, No. 2, 2020, pp. 659-666.
[23] Dal Bianco, N., Bertolazzi, E., Biral, F., and Massaro, M., Comparison of Direct and Indirect Methods for Minimum Lap Time Optimal Control Problems, Vehicle System Dynamics, Vol. 57, No. 5, 2019, pp. 665-696.
[24] Rahaghi, M. I., Barat, F., Solving Nonlinear Optimal Path Tracking Problem Using a New Closed Loop Direct–Indirect Optimization Method: Application on Mechanical Manipulators, Robotica, Vol. 37, No. 1, 2019, pp. 39-61.
COPYRIGHTS
© 2023 by the authors. Licensee Islamic Azad University Isfahan Branch. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution 4.0 International (CC BY 4.0) (https://creativecommons.org/licenses/by/4.0/)