Next Article in Journal
From Mathematical Modeling and Simulation to Digital Twins: Bridging Theory and Digital Realities in Industry and Emerging Technologies
Previous Article in Journal
Research on Cracking Mechanism and Crack Extension of Diversion Tunnel Lining Structure
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Space Discretization Method for Smooth Trajectory Planning of a 5PUS-RPUR Parallel Robot

1
College of Mechanical Engineering, Zhejiang University of Technology, Hangzhou 310023, China
2
Rail Transit Department, Zhejiang Institute of Communications, Hangzhou 311112, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2025, 15(16), 9212; https://doi.org/10.3390/app15169212
Submission received: 16 June 2025 / Revised: 13 August 2025 / Accepted: 20 August 2025 / Published: 21 August 2025
(This article belongs to the Section Robotics and Automation)

Abstract

To improve the dynamic performance of parallel robots in multi-dimensional space, a novel trajectory planning method of space discretization for parallel robots is proposed. First, the kinematic model of the 5PUS-RPUR parallel robot is established. Then, the normalized Jacobian condition number is obtained via the variable weighting matrix method, and is used as the performance metric of path optimization. The weighted sum method is utilized to construct a composite objective function for the trajectory that incorporates travel time and acceleration fluctuations. Next, the position space between the start and end points is discretized, and the robot pose space based on the position points is analyzed via the search method. The discrete pose point weights are assigned according to the condition number. Dijkstra’s algorithm is used to find the path with the minimum condition number. The trajectory optimization model is established by fitting the discrete path with a B-spline curve and optimized via genetic algorithm. Finally, comparative numerical simulations validate the proposed method, which reduces actuator RMS displacement difference by up to 32.9% and acceleration fluctuation by up to 25.6% against state-of-the-art techniques, yielding superior motion smoothness and dynamic stability.

1. Introduction

Lower-mobility parallel kinematic mechanisms present compelling advantages over their 6-DOF counterparts, including simpler architectures and reduced complexity in their design and control [1]. Among these, mechanisms capable of three translational and two rotational (3T2R) movements are particularly valuable, being exceptionally well-suited to a wide array of high-value industrial tasks such as 5-axis machining [2], automated assembly [3], and surgical procedures [4]. Given their deployment in these demanding, high-precision tasks, generating an optimal trajectory becomes paramount to fully exploit the capabilities of these advanced robotic systems. Trajectory planning of the robot aims to generate a series of time action sequences required by tasks with the constraints of time, energy consumption or impact. It can effectively guide robots to move in the best way and promote the wide application of robots in manufacturing, medical treatment, logistics, and other fields [5,6,7]. Point-to-point trajectory planning is the most basic and critical part of robot task execution. However, there are many feasible trajectories because of the multi-degree of freedom of the robot [8,9], thus the difficulty of the trajectory planning problem is to choose the best one.
A diverse range of optimization methods have been applied to this problem. Parametric methods [10], which define the trajectory using functions such as high-order polynomials [11], B-splines [12], or Bézier curves [13], are widely used due to their inherent ability to ensure path smoothness and continuity [14,15]. However, these methods typically require a secondary optimization process to determine the optimal coefficients or control points that satisfy dynamic and kinematic constraints, a task which can itself be complex. In contrast, heuristic and meta-heuristic techniques, often termed intelligent algorithms [16], such as genetic algorithms (GAs) and particle swarm optimization (PSO), exhibit strong global search capabilities and are well-suited to complex, non-convex problem landscapes. Their primary drawbacks include significant computational expense and a sensitivity to parameter tuning, which can affect convergence and solution quality. Convex optimization [17] offers a powerful alternative, guaranteeing global optimality with high computational efficiency for problems where the objective function and constraints can be formulated in a convex form. This requirement, however, is a significant limitation, as many real-world robotics problems are inherently non-convex and must be simplified or approximated to fit the framework. Dynamic programming [18] provides a flexible structure for sequential decision-making but often yields only approximate solutions and can suffer from the curse of dimensionality in systems with many degrees of freedom. Each of these approaches thus presents a distinct trade-off between solution optimality, computational complexity, and the ability to model intricate constraints, motivating the development of hybrid methods that can balance these competing factors. Many scholars combine three basic methods. Considering the dynamics and external force of the robot, Kaserer et al. [19] established the trajectory motion model of the optimal time with jerk as the constraint condition, and used the dynamic programming algorithm to optimize the solution, which can realize the stable and compliant control of the robot. Ma et al. [20] transformed the non-convex acceleration limit into a linear acceleration constraint with the torque and impact limits, and introduced it into the convex optimization as a linear acceleration constraint to improve the calculation efficiency of the algorithm. The simulation results show that compared with the traditional method, the maximum joint torque is reduced by more than 80%, and the joint torque curve is smoother. Cui et al. [21] established a trajectory optimization of a flexible robotic arm using a fifth-order polynomial trajectory, which is optimized through a particle swarm optimization algorithm. The simulation results showed that the vibration amplitude of the trajectory generated by the proposed algorithm was smaller than that of the third-order polynomial. Zhang et al. [22] proposed an efficient trajectory planning framework based on global non-convex optimization. A six-degree-of-freedom serial robot of the motion trajectory planning model based on non-convex optimization is established. Through the non-convex optimization model transformation and the solver based on multiple regression, the calculation time is reduced by about 50% in the best case. Liu et al. [23] proposed time-optimal and jerk-continuous trajectory planning for robot manipulators with kinematic constraints. The joint paths have been obtained by means of cubic splines connecting a number of given discrete characteristic points in Cartesian space. Septuple B-splines were used to fit the joint paths to gain the time-optimal and jerk-continuous trajectory under kinematic constraints. Wang et al. [24] proposed a method for multi-objective trajectory planning using indirect method. Based on the normalized Jacobian condition number, a path with better joint velocity distribution was obtained. Considering travel time, energy consumption and torque fluctuations, a multi-objective optimization model was established using a fifth-order B-spline. The elite non-dominated sorting genetic algorithm was used to optimize the model, which realizes the point-to-point task with faster time, lower energy, and higher stability.
A review of the literature reveals that most studies focus on the overall performance of a robot’s trajectory, often overlooking its state at intermediate moments. This oversight is significant because transient periods of poor motion stability, manifesting as large acceleration fluctuations, abrupt changes in actuator forces, and low energy efficiency. These factors can induce undesirable vibrations in the robot’s structure. This methodology addresses the challenge by first discretizing the robot’s operational workspace. For each discrete point, a search of the corresponding orientation space is conducted, and each resulting pose is assigned a weight based on a dexterity index. To mitigate excessive acceleration between consecutive waypoints, constraints on step transitions are imposed. Dijkstra’s algorithm is then employed to compute an optimal path that maximizes cumulative dexterity, ensuring the robot operates in a highly effective state. Finally, this sequence of waypoints is utilized as the control points for a B-spline, generating a smooth and continuous motion trajectory. Crucially, the discretization process can be completed offline, thereby facilitating real-time, online trajectory planning.
This paper is organized as follows: In Section 2, the discretized trajectory planning method is presented. Dijkstra algorithm is applied to optimize the normalized Jacobian condition number for path planning, and GA is utilized to optimize the objective functions for trajectory planning. In Section 3, the kinematic model of the 5PUS-RPUR (R, P, S, and U stand for revolute, prismatic, spherical, and universal joints) parallel robot is analyzed. Next, the optimization objective functions, including path and trajectory index, are established in Section 4. Subsequently, the numerical simulations are presented with relevant discussion in Section 5. Finally, the main conclusions are offered in Section 6.

2. Kinematic Analysis

2.1. Position Inverse Solution

As shown in Figure 1a, the 5PUS-RPUR parallel robot consists of five PUS branches, a single RPUR branch, a moving platform, and a base. The branched PUS includes a module, a slider, a Hooke hinge 1, a fixed-length rod1, and a spherical pair. The RPUR chain includes an electric cylinder, push rod, Hooke hinge 2, and fixed-length rod 2. As depicted in Figure 1b, the origin O of the static coordinate system O-XYZ is located at the center of the base. The Z-axis is perpendicular to the base and the direction is upward. X-axis points along the origin in the OCi-direction, and Y-axis is determined by the right-hand rule. The origin o of the moving coordinate system o-xyz is located at the center of the moving platform. The z-axis is perpendicular to the moving platform and the direction is upward. The x-axis points along the origin in the direction of the spherical hinge, and the y-axis is determined by the right-hand rule. The coordinate origin Ci of the branched coordinate system Ci-xiyizi is located at the endpoints of the regular pentagon of the base. The yi axis is upward in the direction of module movement, while the xi axis is perpendicular to the yi axis and is located in the base plane, and the zi axis is determined by the right-hand rule.
For ease of understanding, the Euler angle is used to describe the posture transformation of the parallel robot. The spherical pair center point Ai is fixedly connected to the moving platform; its position vector in the static coordinate system can be expressed as
A i O = R P O A i 0 + P
where the coordinate transformation matrix is R P O = R ( x , α ) R ( y , β ) R ( z , γ ) , and α, β, and γ (γ = 0) is the Euler rotation angle of the moving platform around the x, y, and z axes of the moving coordinate system. 0Ai (i = 1~5) represents the position vector of the center of the spherical pair in the static coordinate system, and P represents the position vector of the origin of the dynamic coordinate system in the static coordinate system.
The position vector of the center point Bi of Hooke pair 1 in the static coordinate system can be expressed as
B i O = C i O + R C i O B i C
where 0Ci denotes the position vector for the origin Ci of the branch coordinate system in the static coordinate system, CBi denotes the position vector of the center of the Hooke pair in the branched coordinate system, and the rotation matrix from the branch coordinate system to the static coordinate system is R C i O = R ( z i , δ i ) R ( y i , 0 ) R ( x i , φ ) , δi = 18° + i × 72°, φ = 30°.
The position vector of the Hook pair center Bi in the branched coordinate system is
B i C = 0 l B y 0 + Δ L i l B z 0 T
where ΔLi denotes the actuator displacement of the i -th branched chain. lBy0 and lBz0 denote the distance of the Hook pair center in the direction of yi axis and zi axis at the initial moment.
Due to AiBi being the fixed rod, the length of the fixed rod can be expressed as
L = A i O B i O
where |·| represents the vector norm. Substituting Equations (1) and (2) into Equation (4), the inverse position solution of the PUS chain is obtained, and the input displacement ΔLi can be obtained by the given pose of the moving platform.
Since the configuration of the RPUR chain does not satisfy the Pieper criterion, it cannot be solved by means of the PUS chain analysis. The Denavit–Hartenberg (D-H) method and elimination method are combined for analysis in this paper. First, as shown in Figure 2, five coordinate systems of connecting rods are constructed for the rotating pair, moving pair, Hook pair, and prismatic pair. Second, the five-dimensional equations are obtained through the algebraic relationship between the displacement of each kinematic pair and the dynamic coordinate system. Finally, the displacement of each kinematic pair can be obtained by elimination.
The pose transformation matrix of the PUS chain in the branched coordinate system can be expressed as
T P O = T 5 0 = T 1 0 T 2 1 T 3 2 T 4 3 T 5 4
with   T P O = R 0 P 0 0 1 ,   T 1 0 = R 1 P 1 0 1 ,   T 2 1 = R 2 P 2 0 1 T 3 2 = R 3 P 3 0 1 ,   T 3 4 = R 4 P 4 0 1 ,   T 4 5 = R 5 P 5 0 1 ,
where R0 = R(y, β)R(x, α), P0 = P. R1 = R(x, θ1), P1 = [0 0 0]T. R2 = E3, P2 = [0 0 a1 + θ2]T. R3 = R(z, π)R(x, θ3), P3 = [0 0 a2 + θ2]T. R4 = R(z, π/2)R(x, θ4), P4 = [0 0 0]T. R5 = R(z, π/2)R(y, θ5), P5 = [0 0 a3]T. θ1, θ2, θ3, θ4, and θ5 represent the displacement of each joint of the RPUR chain, a1, a2, and a3 represent the distance between the origin of each connecting rod coordinate system, and E3 represents a 3-order unit matrix.
From the equality of both ends of Equation (5), the joint displacements θ4 and θ5 can be obtained after elimination.
θ 4 = arcsin x a 3 θ 5 = β θ 4
Obtaining the displacement of the last two joints, the moving platform reference point P is given, so Equation (5) can be rewritten as
T 1 0 T 2 1 T 3 2 = T P O T 3 5
The joint displacements θ4 and θ5 are regarded as known parameters; the coordinates of the center position for Hooke pair 2 in the static coordinate system can be expressed as
D O = s θ 5 x c θ 5 y c θ 4 c θ 5 x s θ 5 c θ 4 y s θ 4 z s θ 4 ( a 1 + a 2 ) s θ 4 c θ 5 x s θ 4 s θ 5 y + c θ 4 z + c θ 4 ( a 1 + a 2 )
where sx = sin x, cx = cos x.
The center position of the Hooke pair is represented by the displacement for the first three kinematic pairs of the RPUR chain, thus the actuator displacement of the RPUR chain can be expressed as
θ 2 = D O a 1 + a 2 + a 3

2.2. Velocity Analysis

Given the trajectory of the moving platform, for the PUS chain, the reference point P on the moving platform and the center point Ui of Hooke pair 1 are taken as the base points. The linear velocity of the center of the spherical pair can be expressed as
v A i = v P + ω P × A i = v i e i + ω i × l i L
where ωP and vP are the angular and linear velocities of the reference point P on the moving platform. vi denotes the module velocity in the i-th PUS chain, ei denotes the module unit direction vector in the i-th PUS chain, ωi denotes the angular velocity of the fixed-length rod 1 in the i-th PUS chain, and li and L are the unit direction vector and length of the fixed-length rod AiBi.
Taking the left dot product of Equation (10) with l i T , we can obtain
v i = l i T v P + ω P × A i l i T e i = J V i ω P v P
with   J V i = l i T l i T e i A i × l i T l i T e i T .
The Jacobian matrix of the parallel mechanism can be expressed as
J = J V 1 J V 2 J V 3 J V 4 J V 5 T
Taking the right cross product of Equation (10) with li, we get
ω i = v P + ω P × A i × l i L = J ω i ω P v P
with   J ω i = l ˜ i ( J A i e i J V ) L ,   J A i = E 3 A ˜ i T .
where l ˜ i and A ˜ i denote the skew-symmetric array of matrices li and Ai.
For the velocity analysis of the RPUR chain, taking the center point D of Hooke pair 2 as the analysis object, its velocity can be expressed as
v D = v P + ω R 5 × D P = ω R 1 × v 6 + a 1 + a 2 e 6
where D = (v6 + a1+ a2)e6, ωR1, and ωR5 are the angular velocity of the first and last rotating pair of the RPUR chai. v6 and e6 represent the velocity and the unit direction vector of the prismatic pair in the RPUR chain.
According to Equation (14), the velocity of the prismatic pair can be expressed as
v 6 = v P + ω R 5 × D P ω R 1 × e 6 a 1 a 2

2.3. Acceleration Analysis

The acceleration of the actuator can be obtained by deriving the input velocity. Equation (1) is derived to obtain
a A i = a P + ε P × A i + ω P × ω P × A i = a i e i + ε i × l i L + ω i × ω i × l i L
Taking the left dot product of Equation (16) with l i T , the algebraic relationship between the input and output velocity of the PUS chain can b be expressed as
a i = J v ε P a P + ω P v P T J a ω P v P
with   J a = 0 3 × 3 0 3 × 3 0 3 × 3 l ˜ i × A ˜ i L J ω T l i 2 J ω l i T e i .
Taking the right cross product of Equation (16) with li, the mapping relationship between input and output angular velocity can be obtained.
ε i = J ω J ε ω P v P + l ˜ i ω P × ω P × A i L
with   J ε = l ˜ i e i ω P v P T J a L .
For the RPUR chain, taking derivation of Equation (15), the velocity mapping relationship between the actuator joint and the moving platform can be expressed as
a 6 = a P + ε R 5 × D P + ω R 5 × ω R 5 × D P ω R 1
with   ω R 5 = β ˙ 1 x 2 / a 3 2 1 ,   ε R 5 = β ¨ 2 x / a 3 2 x 2 .

3. Objective Function

3.1. Path Optimization Index

The precondition for discrete trajectory planning is to select a path of optimal performance, and the key lies in the selection of the performance index and global optimal path. The dexterity reflects the transfer relationship between the input and output motions of the mechanism, which can be used as a performance indicator for evaluating the local operability of parallel robots. The Jacobian matrix is usually used as a quantitative index for dexterity. However, for robots with mixed degrees of freedom, the Jacobian matrix dimension is not uniform, so it cannot be directly used for the dexterity analysis.
The 5PUS-RPUR parallel mechanism contains only 5 degrees of freedom, whose Jacobian matrix J is a high matrix form of 5 × 6 in Equation (12); thus, there is column correlation. The reason for column correlation is that the parallel robot is always constrained by the z-axis direction of the rotating platform. Using the Euler angle to describe the posture, the real Jacobian matrix JP can be expressed as
J P = J G ω = J G ω 0 3 0 3 × 2 E 3 6 × 5
with   G ω = 1 0 0 0 cos α sin α T .
The variable weighting matrix method [24] is used to construct a normalized Jacobian matrix. Using the elements of the Jacobian matrix itself in Equation (20), the weighting matrix can be expressed as
W V = 1 L r E 2 0 0 1 L t E 3 5 × 5
with   L r = 1 2 c = 0 5 J P 1 , 2 2 ,   L t = 1 3 c = 0 5 J P 3 , 4 , 5 2 ,
where J P 1 , 2 and J P 4 , 5 , 6 denote the matrices consisting of columns from 1 to 2 and from 4 to 6 of the matrix JP, respectively. E2 is a 2-order unit matrix.
Taking the left dot product of the Jacobian matrix with WV, the normalized Jacobian matrix can be obtained.
J ¯ = W V J
The 2-norm and Frobenius norm are widely used in the computation of condition numbers. Compared with the 2-norm, the Frobenius norm of the Jacobian arguments is an analytic function, which can reduce the computational effort without calculating the singular values of the matrix. Therefore, this Frobenius norm is used as the optimization calculation. From Equation (22), the condition number of Jacobian matrix can be expressed as
k ( J ) = 1 n tr J ¯ T J ¯ tr J ¯ 1 ( J ¯ 1 ) T
It should be noted that this normalization and condition number calculation is performed independently for each discrete pose in the search space, ensuring that the path-finding is not biased by the initial robot configuration.

3.2. Trajectory Optimization Index

In general, it is expected that the trajectory of the parallel robot is smooth enough to avoid excessive mechanical vibration and the traveling time is as short as possible to improve production efficiency. Taking time integration and acceleration fluctuation as two objective functions of trajectory optimization, the mathematical expression is
f 1 t = T = 0 t d t f 2 t , ψ = i = 1 n 0 T a i t , ψ a i t 1 , ψ d t
where f1 is the total travel time. f2 is the variance of acceleration, which serves as a direct proxy for motion stability. Minimizing this term inherently leads to a more dynamically stable motion. ψ represents the robot’s pose. ai(t, ψ) and ai(t − 1, ψ) denote the acceleration of the actuator joint in the original and the current motions, respectively. n is the number of actuator joints.
It is clear that these two objective functions are constrained by each other, as they act in opposite ways. The decrease of the travel time will lead to larger acceleration fluctuation and the non-smooth trajectory. The decrease in acceleration fluctuation will result in the extension of execution time and lower efficiency. Trajectory planning inevitably encounters a trade-off between these two objective functions. Using the weighted summation method to solve the multi-objective optimization problem, the comprehensive objective function can be expressed as
k ( T ) = δ 1 f 1 + δ 2 f 2
where δ1 and δ2 are the non-negative weighting coefficients that define the relative importance of travel time and acceleration fluctuations, respectively. These weights allow the optimization to be tailored to specific task requirements. For instance, a higher value for δ1 would prioritize a faster trajectory, whereas a higher δ2 would favor a smoother, more stable motion. In the numerical simulations that follow, we assume a balanced trade-off is desired and therefore set δ1 = δ2 = 0.5, giving equal consideration to both objectives.

4. Trajectory Planning Method

Parallel robots are required to move sequentially from one target point to another in most practical situations. Since parallel robots have multiple degrees of freedom, there exist multiple feasible motion trajectories. In order to obtain an optimal trajectory with a short execution time and smooth contour, a multi-objective trajectory optimization method is proposed in this paper. The framework is shown in Figure 3. The main idea of the proposed point-to-point trajectory optimization method is to construct a path with the best static performance between two pose points, and allocate the time rule to the previously obtained geometric path according to the expected dynamic index. The method can be divided into two steps. First, a kinematic model of the parallel robot is developed and the desired path objective function is defined based on the model. The space between the given start position and end position is discretized, and the attitude workspace is searched at each position point. The path objective function is used to assign weights to each pose point, and the optimal set of discrete path points is obtained by searching the pose points based on the Dijkstra algorithm. Then, the optimal discrete path points are used as the control points of the B-spline curve. The dynamic comprehensive objective function is established with the kinematic constraints. The trajectory optimization model is constructed and solved to obtain the optimal trajectory by using the genetic algorithm.

4.1. Path Planning

Assuming that the starting position of the moving platform of the parallel robot is φ0 = [x0, y0, z0] and the ending position is φf = [xf, yf, zf], the positional region from the starting point to the ending point is discretized. Different positional paths are represented by various combinations of discrete points, and the discretization step sizes are set as
Δ ζ x = x f x o n 1 ,   Δ ζ y = y f y o n 2 ,   Δ ζ z = z f z o n 3
where Δζx, Δζy, and Δζz denote the discrete steps in the x, y, and z directions, respectively, and n1, n2, and n3 denote the number of discrete steps in the directions, respectively. It should be noted that the α and β directions should be set as the maximum change of value single step Δζα max and Δζβ max.
Each discrete point is labeled based on its positional relationship, as shown in Figure 4. There exist a start point, six pass points, and an end point for each discrete cell, and the respective pose space is searched based on these position points using the searching method [25]. A path grid can be constructed from the starting point to the endpoint through the unit labeling rules. Each discrete point within the grid can represent multiple condition number indicators k(J) of the parallel robot with different poses. The number of indicators at the discrete points is consistent with the number of points in their pose space, and k(J) is defined as the weight of that discrete point. The sum of the indicators k(J) at all discrete points along the path represents the performance of that path. The smaller the path performance indicator, the better the performance of the path.
The path rule for discrete units is shown in Figure 5. The discrete point of the cube starts from the start point and passes through the passage point to arrive at the end point of the unit, there is no return and a total of 13 paths. The 13 unique path rules for traversing a discrete position cell. Each subfigure, (a) through (m), illustrates a distinct, valid sequence of movements for traversing a single discrete cell, from the start node (bottom-front-left corner) to the end node (top-back-right corner). These paths are constructed by connecting the nodes along the cell’s edges without backtracking, representing the fundamental set of local choices available to the path-finding algorithm. For instance, path (a) represents a sequence of movements first along the x-axis, then the z-axis, and finally the y-axis, whereas path (b) shows a sequence of the x-axis, then diagonal between the z-axis and the y-axis. The global path across the entire workspace is constructed as a concatenation of these elemental cell-traversal paths.
The optimal path, defined as the one with the minimum cumulative condition number, is determined using Dijkstra’s algorithm. The process, illustrated in the flowchart in Figure 6, proceeds as follows:
Initialization: The algorithm commences by establishing the graph of all discrete pose points, each assigned a weight corresponding to its calculated condition number. Two sets are created: a ‘visited’ set, initially containing only the starting pose φ0, and an ‘unvisited’ set containing all other poses. The cumulative path cost to φ0 is set to its own weight, while the cost to all other nodes is initialized to infinity.
Iterative Search: The algorithm then enters an iterative loop. In each iteration, it examines all unvisited nodes that are adjacent to the nodes in the visited set. It performs a greedy selection, identifying the unvisited node that can be reached with the lowest cumulative path cost from the start node φ0.
Update: This selected node is then moved from the unvisited set to the visited set. Following this, the algorithm updates the cumulative path costs for all of the newly visited node’s neighbors, if a shorter path is found by routing through it.
Termination and Output: The loop continues until the end point φf is moved to the visited set. At this point, the algorithm terminates, and the optimal sequence of discrete pose points is reconstructed by backtracking from the end point to the start point.
The trajectory composed of a series of discrete points by the planned path is not smooth. The discrete points are used as the control points of the B-spline curve to construct the trajectory of the moving platform, and the optimal trajectory can be obtained from the starting point to the end point.

4.2. Trajectory Planning

Higher order B-spline has many advantages in trajectory interpolation. For example, changes in local support and one control point do not affect the entire fitting function, thus ensuring that the curve is closer to all control points. Meanwhile, the B-spline can provide the smoothness of the joint space trajectory, so as to ensure the motion stability of the mechanism. Therefore, the B-spline is selected for trajectory planning. In addition, the fifth-order B-spline is selected for trajectory optimization in order to achieve the function of arbitrary configuration for velocity and acceleration at the start and end points of the trajectory.
According to m end-effort pose optimized by the discrete path, applying the inverse kinematic model to obtain the actuator displacement, and the matching time series is [t1, t2, …, tm]. Interpolation of m points pi with k times B-spline curve. In addition, k nodes are added at both ends, in order to make the trajectory parameters of the trajectory endpoint controllable. The trajectory can be expressed as
p i = p ( u i + k ) = j = i i + k 1 d j N j , k u i + k , u i + k u k , u q + k
with   u i = 0 , i = 0 ,   1 ,   , k u i 1 + ( t i k t i k 1 ) / ( t m t 1 ) , i = k ,   k + 1 ,   , m + k 2 1 , i = m + k 1 ,   m + k ,   , m + 2 k 1 ,
where k denotes the order of the B-spline function. dj (j = 0, 1,…, m + k − 2) is the control point of the B-spline curve to be solved. ui represents the variable of the normalized node vector, which can be obtained by the cumulative chord length method. Nj,k(ui+k) is a B-spline basis function calculated by the Cox–de Boor regression formula [26].
The construction of the entire spline curve requires (m + k − 1) control points, Equation (27) gives the m equations, and additional (k − 1) equations can be constructed by boundary conditions at the starting and ending points. The boundary conditions include kinematic constraints on velocity and acceleration at two terminal moments. The boundary conditions can be obtained by taking the r-order derivative pr(u) of the B-spline at both ends, and its derivative can be expressed as
p r ( u ) = j = i k + r i d j r N j , k r u , u u k , u q + k
where ,   d j l = d j l = 0 ( k r + 1 ) ( d j l 1 d j 1 l 1 ) u j + k l + 1 u j ,   l = 1 , 2 ,   ,   r j = i k + r , i k + r + 1   , i .
With the boundary condition of the B-spline curve in Equation (28), the kinematic constraints of velocity and acceleration can be derived as
V ( t 0 ) = p ˙ u u = u k = j = k k + 1 k d j 1 N j , k 1 ( u k ) = d 1 1
V ( t m ) = p ˙ u u = u m + k = j = m + k 2 k + 1 m + k 2 d j 1 N j , k 1 ( u m + k 1 ) = d q + k 2 1
A ( t 0 ) = p ¨ u u = u k = j = k k + 2 k d j 2 N j , k 2 ( u k ) = d 2 2
A ( t m ) = p ¨ u u = u m + k = j = m + k 2 k + 1 m + k 2 d j 2 N j , k 2 ( u m + k 1 ) = d q + k 2 1
where V(t0), V(tm), A(t0), and A(tm) indicate the velocity and acceleration of the joint actuator at the start and end positions, respectively, and can be calculated by recursive Equation (28).
Kinematic constraints include the limits of velocity and acceleration. In order to ensure the start and stop stability of the parallel robot, the velocity and acceleration of these positions are set to zero. A k-order B-spline curve is always contained in a convex envelope of its control points, and the constraints can be expressed as
max ( | d j m 1 | ) sup | V max | , j = 1 , 2 ,   ,   n + k 1
max ( | d j m 2 | ) sup | A max | , j = 1 , 2 ,   ,   n + k 1
V ( t 0 ) = A ( t 0 ) = 0 , V ( t m ) = A ( t m ) = 0
where d j m 1 and d j m 2 denote the j-th control point of the velocity and acceleration of the B-spline curves in the m-th joint, Vmax and Amax denote the maximum velocity and acceleration of the m-th joint actuator.
Adding 4 nodes to both ends of a fifth B-spline curve to create a trajectory curve, the velocity and acceleration of the trajectory at the initial and final moments can be arbitrarily configured as needed. Equation (35) can be considered as four boundary conditions, and Equations (33) and (34) are kinematic constraints.
The discrete point path of the optimal static performance is obtained based on Dijkstra’s algorithm. On this basis, the trajectory optimization model is constructed using the fifth B-spline curve. The genetic algorithm is used to optimize the solution. The initial conditions of the algorithm are set, including the initial population, the number of iterations, the crossover factor, and the mutation factor. Then, the optimal trajectory of dynamic performance is obtained after optimization. Subsequently, taking a 3T2R five-degree-of-freedom parallel robot as an example, the proposed trajectory planning method is validated and the feasibility of the method is demonstrated through simulations.

5. Numerical Simulations and Discussions

To validate the proposed method (PM), its performance is benchmarked against three established algorithms: the fifth-order polynomial (FP) [27], triple NURBS curves (TNC) [28], and a combined cubic-septuple B-spline approach (CCS) [23]. The following sections detail the algorithm’s implementation and provide a systematic comparison of the results.

5.1. Implementation of the Trajectory Planning Algorithm

The simulation is configured using the specific dimensional parameters of the 5PUS-RPUR parallel robot, as detailed in Table 1. The point-to-point planning task is defined by the robot’s initial pose, ψ0 = [0, 0, 0.76, 0, 0]T, and its final pose, ψƒ = [0.05, 0.05, 0.86, −0.3π, −0.3π]T, where positional components are in meters and orientational components are in radians. To ensure physically realizable motion, kinematic constraints are imposed, with the maximum velocity and acceleration of the moving platform set to 0.05 m/s and 0.04 m/s2, respectively.
To find an optimal path, the workspace is first discretized. The Cartesian space between the start and end positions is divided into n1 = 10, n2 = 10, and n3 = 10 segments along the x, y, and z axes, respectively. This process created a grid containing a 11 × 11 × 11 mesh of discrete position nodes. At each of these nodes, a search is conducted to identify the set of reachable orientations, with a search precision of 0.01 rad. It should be noted that the choice of discretization steps and precision is determined by the specific requirements of the robotic task, balancing the need for accuracy against computational efficiency.
With the pose space established, Dijkstra’s algorithm is employed to determine the optimal path. The dexterity index, defined in Equation (23), is used as the cost metric, with each discrete pose in the grid being assigned a corresponding weight. Commencing from the initial pose, the algorithm iteratively explores the grid, identifying the path with the minimum cumulative dexterity cost. The resulting sequence of discrete optimal position points found by the algorithm is shown in Figure 7. Figure 7 presents the resulting three-dimensional path. The discrete waypoints identified by Dijkstra’s algorithm (orange) form the coarse path, while the final, optimized B-spline trajectory (blue) represents a smoothed interpolation of this path. It is evident that the B-spline acts to round the sharp corners of the waypoint sequence, producing a continuous curve.
Finally, to generate a smooth and continuous trajectory, this sequence of optimal poses is used as the control points for a quintic B-spline curve. The trajectory is further constrained by enforcing zero velocity and acceleration at the start and end points. The resulting three-dimensional position path of the moving platform is shown as the continuous curve, while the individual path curves for each degree of freedom (x, y, z, α, and β) are presented in Figure 8. Figure 8 provides a more detailed analysis by decomposing this trajectory into its constituent translational and rotational components. In Figure 8a, the monotonic progression of the x, y, and z coordinates illustrates a direct and efficient spatial movement. The smoothness of these curves indicates continuous velocity profiles, free from any sudden jerks. Similarly, Figure 8b shows the evolution of the orientation angles, α and β. Their smooth, bell-shaped profiles demonstrate that the robot’s end-effector undergoes a controlled and gradual reorientation, avoiding any abrupt rotational changes that could induce vibration or instability. Together, these results confirm that the proposed method successfully translates the discrete, kinematically-optimal waypoints into a single, smooth, and stable motion trajectory.
The GA is employed to optimize the parameterized trajectory model. While the composite function k(T) from Equation (25) defines objectives, using it directly as a fitness function presents challenges related to scaling and commensurability. To ensure that neither objective dominates the optimization due to its numerical scale and to reconcile their different physical units, each objective term is first normalized to a common range using min-max scaling. Furthermore, to handle the kinematic constraints on velocity and acceleration (Equations (33) and (34)) within the GA’s unconstrained optimization framework, an exterior penalty function method is applied. This combines the normalized objectives and the penalty terms into a single, comprehensive fitness function, which can be expressed as
f P ( T ) = δ 1 f 1 f 1 min f 1 max f 1 min f 1 + δ 2 2 f 2 f 2 min f 2 max f 2 min + G max max ( | d j m 1 | ) sup | V max | , 0 + H max max ( | d j m 2 | ) sup | A max | , 0
where f1min/f1max and f2min/f2max are the minimum and maximum values of their respective objective functions, determined across the population in each generation. The terms G and H are large positive penalty factors, chosen to apply a significant cost to any solution that violates the kinematic constraints.
The efficiency and stability are considered to be equally important, so the weight coefficients δ1 and δ2 are set to 0.5. The key task of the GA is to optimize the time intervals of the control points, Δti, between each pair of consecutive control points, subject to the robot’s velocity and acceleration constraints. The chromosome for the GA is a vector representing these time intervals. According to Ref. [24], the initialization parameters of GA are as follows: population size = 200, generation number = 80, crossover probability = 0.8, mutation probability = 0.05. The optimal time is determined as 2.37 s (Table 2) and the minimum acceleration fluctuation value f2 is 1.80 m/s2.
By applying an inverse kinematic transformation to the optimized trajectory, the corresponding joint-space velocity and acceleration profiles for each actuated joint are obtained, as presented in Figure 9 and Figure 10, respectively.
Figure 9 displays the velocity profiles of the six actuated joints. Each curve is smooth and continuous, beginning and ending at zero velocity, which is essential for a stable start-stop motion. The differing peak velocities among the joints are a direct consequence of the robot’s kinematics, reflecting the varying displacements required from each actuator to achieve the desired end-effector path.
Figure 10 presents the corresponding joint acceleration profiles. The continuity and smoothness of these curves are of particular importance, as they directly validate the success of our optimization objective to minimize acceleration fluctuation. The absence of any discontinuities signifies a low-jerk motion, which is critical for reducing mechanical stress, mitigating vibration, and ensuring high-precision tracking. Furthermore, the zero-acceleration boundary conditions guarantee a smooth transition from and to a stationary state.

5.2. Comparative Analysis of Path Smoothness

The first point of comparison focuses on the smoothness of the joint-space paths generated by the PM, FP, TNC, and CCS. To ensure a direct and equitable comparison, several experimental conditions are standardized. The total travel time is set to be consistent across all methods, and all trajectories are defined with identical boundary conditions, requiring zero velocity and acceleration at both the initial and final configurations. Furthermore, uniform kinematic limits for velocity and acceleration are applied across all actuated joints.
The evaluation process first involved generating the moving platform trajectories using each of the four algorithms. Subsequently, an inverse kinematic transformation is applied to convert these platform trajectories into the required input profiles for each actuated joint, which are illustrated graphically in Figure 11. For a further quantitative assessment of the proposed method’s advantages, the Root Mean Square (RMS) value of each joint displacement profile is calculated. These results are systematically summarized in Table 3.
The quantitative data presented in Table 3 corroborate the qualitative insights from Figure 11. For every actuated joint, the PM yields a lower or highly competitive RMS value. Notably, for joint θ5, the PM achieves an RMS value of 0.00291, representing a 32.9% reduction compared to the FP method and a 7.6% reduction versus CCS. This suggests that the PM achieves the required displacement more efficiently, potentially leading to benefits such as reduced energy consumption, lower peak actuator torques, and smoother overall system operation.
The superior motion efficiency demonstrated by the PM is a direct outcome of our dexterity-first approach. Conventional methods, such as those presented by Refs. [23,27,28], focus on ensuring the geometric smoothness of the trajectory using splines or polynomials. While effective at creating continuous paths, these methods do not inherently consider the robot’s kinematic state along that path. Consequently, they can produce trajectories that, while smooth, are inefficient in the joint space. Our method addresses this by first finding a path that explicitly maintains high manipulability, thereby avoiding configurations that would require large and inefficient joint movements.

5.3. Comparison of Dynamic Stability and Computational Efficiency

The second comparison discusses and compares the results for acceleration fluctuation and computational cost. Figure 12 presents the instantaneous acceleration fluctuation for each of the four methods over the duration of the trajectory. While all methods produce a continuous, smooth profile, the qualitative differences are clear. The curves corresponding to the FP, TNC, and CCS methods exhibit significantly higher peaks, particularly during the central phase of the motion where accelerations are greatest. In contrast, the curve for our proposed method (PM) remains consistently lower throughout the entire maneuver. This demonstrates that our method does not merely achieve a better result in aggregate, but actively produces a motion with smaller instantaneous changes in acceleration at every stage. This behavior directly translates to a superior, smoother trajectory with reduced jerk. The integrated effect of this is the significantly lower total acceleration fluctuation value, with our method yielding reductions of 25.6%, 18.3%, and 14.7% when compared to FP, TNC, and CCS, respectively. This approach is also applicable to other serial, parallel, and mixed-architecture mechanisms.
The computational complexity is another critical metric for evaluating a trajectory planning algorithm. The proposed method (PM) can be divided into two main stages: offline path planning and online trajectory optimization.
Offline Stage: This stage involves discretizing the workspace, searching the pose space at each discrete position point, and running Dijkstra’s algorithm to find the optimal path based on the condition number. The computational cost of this stage is primarily dependent on the discretization resolution (n1, n2, n3) and the density of the pose search. For the simulation in this paper (n1 = n2 = n3 = 10), this process takes approximately 20 min on a standard desktop computer (Intel i7-11800H, 16 GB RAM (Intel, Santa Clara, CA, USA)). However, this is a one-time, offline computation that can be performed in advance for a known workspace and task, and the resulting optimal path can be stored for repeated use.
Online Stage: This stage involves using the GA to optimize the time intervals of the B-spline curve that fits the discrete path points. The cost of this stage is what truly matters for real-time or near-real-time applications.
To ensure a rigorous and fair comparison, a consistent set of boundary conditions and constraints is applied to all evaluated methods. Specifically, all algorithms are tasked with planning between the same start and end poses, with zero velocity and acceleration at both terminals. Crucially, to normalize the comparison against the time-smoothness trade-off, the total travel time is fixed. The optimal time of 2.37 s, as determined by the proposed method, is set as a mandatory time constraint for the FP, TNC, and CCS methods. The objective for each method is then to find the trajectory that minimized acceleration fluctuations within this fixed duration. This benchmark specifically covered the calculation of the complete kinematic profile, which involves the displacement, velocity, and acceleration of the actuated joints of the 5PUS-RPUR parallel robot. The results are summarized in Table 3.
As shown in Table 4, the FP method is computationally the fastest, as it involves solving a determined set of linear equations without iterative optimization. The PM, TNC, and CCS all rely on intelligent optimization algorithms, resulting in comparable online computation times. Although our method’s online stage is not the fastest, it is important to consider the trade-off: this slight increase in computation time yields a significant reduction in acceleration fluctuation and ensures the robot operates in high-dexterity configurations.
The significant reduction in acceleration fluctuation highlights a key advantage of decoupling the path and trajectory planning problems. Holistic optimization approaches (Refs. [23,27,28]), which solve for geometry and time simultaneously, can overlook transient periods of instability. Our framework prevents this by first securing a kinematically sound path, ensuring that the subsequent time optimization operates on a foundationally stable route. The result is a trajectory with enhanced dynamic stability, which is paramount for high-precision tasks. In terms of computational cost, the PM represents a strategic trade-off. The most demanding computations are performed offline, which is a practical approach for known industrial tasks. The online time, while not the absolute fastest, is comparable to other intelligent optimization algorithms and is justified by the substantial improvements in motion quality.

6. Conclusions

In this paper, a novel discrete trajectory planning method is proposed to address a key limitation in existing literature, where holistic optimization approaches can result in locally optimal trajectories and neglect performance at intermediate states. Our contribution is a decoupled planning framework by first planning a globally optimal geometric path based on the Jacobian condition number before optimizing the trajectory’s time parameterization. This two-stage approach ensures the robot remains in a high-performance configuration throughout its entire motion. The feasibility and effectiveness of this method are verified through simulations on a 5PUS-RPUR parallel robot, demonstrating its ability to achieve more stable performance in point-to-point tasks.
(1) The efficacy of the proposed method stems from its two-stage, decoupled structure. Initially, by assigning a kinematic performance metric to each discrete pose, Dijkstra’s algorithm is employed to efficiently compute a globally optimal path that prioritizes high dexterity. This ensures that the robot maintains a high level of manipulability throughout the entire maneuver, not merely at its endpoints. Subsequently, the B-spline curve is used to interpolate these discrete waypoints, guaranteeing the geometric smoothness of the final path. This approach is highly efficient as it decomposes a complex optimization problem into two distinct and more manageable stages.
(2) A direct consequence of this dexterity-optimized path is the superior smoothness of the final trajectory. By ensuring the robot operates in a state of high manipulability at all times, its physical advantages are fully exploited, allowing it to execute the required motion with maximum kinematic efficiency. This inherent efficiency means that the desired motion can be achieved with smaller and more gradual changes in actuator commands, which in turn leads to the lowest acceleration fluctuation value when compared to other methods. This minimization of acceleration variance directly corresponds to an enhancement in the robot’s dynamic motion stability, guaranteeing smoother operation and reducing the propensity for performance-degrading vibrations.
Future investigations will be directed towards bridging the gap between kinematic planning and dynamic execution. A robust tracking controller will be developed to calculate and manage the required actuator forces and torques. This system will be rigorously tested for its performance under changeable payloads and its stability during repetitive reference trajectories, ensuring its suitability for demanding industrial applications.

Author Contributions

Conceptualization, J.R. and S.L.; methodology, Y.L. and J.B.; validation, J.B. and S.L.; formal analysis, Y.L. and S.L.; investigation, J.R. and J.B.; data curation, Y.L. and J.R.; writing—original draft preparation, Y.L. and S.L.; writing—review and editing, J.R. and J.B.; visualization, J.B. and Y.L.; supervision, J.R.; project administration, S.L. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Key Research and Development Program of China, grant number 2019YFB2005202.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The raw data supporting the conclusions of this article will be made available by the authors on request.

Acknowledgments

The authors would like to thank the reviewers and the editor, whose suggestions greatly improved the manuscript.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Diego, P.; Macho, E.; Herrero, S.; Campa, F.J.; Diez, M.; Corral, J.; Pinto, C. Kinematic and Workspace Analysis of RRU-3RSS: A Novel 2T2R Parallel Manipulator. Appl. Sci. 2024, 14, 9491. [Google Scholar] [CrossRef]
  2. Chen, K.; Wang, R.; Niu, Z.; Wang, P.; Sun, T. Topology design and performance optimization of six-limbs 5-DOF parallel machining robots. Mech. Mach. Theory 2023, 185, 105333. [Google Scholar] [CrossRef]
  3. Cheng, P.; Cao, W.-A.; Liu, D.; Cui, J.; Lai, J. A Novel Delta-Like Parallel Robot with Three Translations and Two Pitch Rotations for Peg-in-Hole Assembly. J. Mech. Robot. 2025, 17, 021014. [Google Scholar] [CrossRef]
  4. Piccin, O.; Bayle, B.; Maurin, B.; de Mathelin, M. Kinematic modeling of a 5-DOF parallel mechanism for semi-spherical workspace. Mech. Mach. Theory 2009, 44, 1485–1496. [Google Scholar] [CrossRef]
  5. Chen, K.; Wang, M.; Huo, X.; Wang, P.; Sun, T. Topology and dimension synchronous optimization design of 5-DoF parallel robots for in-situ machining of large-scale steel components. Mech. Mach. Theory 2023, 179, 105105. [Google Scholar] [CrossRef]
  6. Wang, C.; Puranam, V.R.; Misra, S.; Venkiteswaran, V.K. A Snake-Inspired Multi-Segmented Magnetic Soft Robot Towards Medical Applications. IEEE Rob. Autom. Lett. 2022, 7, 5795–5802. [Google Scholar] [CrossRef]
  7. Zhang, J.; Luo, H.; Xu, J. Towards fully BIM-enabled building automation and robotics: A perspective of lifecycle information flow. Comput. Ind. 2022, 135, 103570. [Google Scholar] [CrossRef]
  8. Ekrem, O.; Aksoy, B. Trajectory planning for a 6-axis robotic arm with particle swarm optimization algorithm. Eng. Appl. Artif. Intell. 2023, 122, 106099. [Google Scholar] [CrossRef]
  9. Wen, Y.; Pagilla, P. Path-Constrained and Collision-Free Optimal Trajectory Planning for Robot Manipulators. IEEE Trans. Autom. Sci. Eng. 2023, 20, 763–774. [Google Scholar] [CrossRef]
  10. Schperberg, A.; Di Cairano, S.; Menner, M. Auto-Tuning of Controller and Online Trajectory Planner for Legged Robots. IEEE Rob. Autom. Lett. 2022, 7, 7802–7809. [Google Scholar] [CrossRef]
  11. Wang, H.; Wang, H.; Huang, J.; Zhao, B.; Quan, L. Smooth point-to-point trajectory planning for industrial robots with kinematical constraints based on high-order polynomial curve. Mech. Mach. Theory 2019, 139, 284–293. [Google Scholar] [CrossRef]
  12. Li, X.; Gao, X.; Zhang, W.; Hao, L. Smooth and collision-free trajectory generation in cluttered environments using cubic B-spline form. Mech. Mach. Theory 2022, 169, 104606. [Google Scholar] [CrossRef]
  13. Dinçer, Ü.; Çevik, M. Improved trajectory planning of an industrial parallel mechanism by a composite polynomial consisting of Bezier curves and cubic polynomials. Mech. Mach. Theory 2019, 132, 248–263. [Google Scholar] [CrossRef]
  14. Huang, Y.; Ke, J.; Zhang, X.; Ota, J. Dynamic Parameter Identification of Serial Robots Using a Hybrid Approach. IEEE Trans. Rob. 2023, 39, 1607–1621. [Google Scholar] [CrossRef]
  15. Kim, J.-J.; Lee, J.-J. Trajectory Optimization with Particle Swarm Optimization for Manipulator Motion Planning. IEEE Trans. Ind. Inf. 2015, 11, 620–631. [Google Scholar] [CrossRef]
  16. Singh, G.; Banga, V.K. Kinematics and trajectory planning analysis based on hybrid optimization algorithms for an industrial robotic manipulators. Soft Comput. 2022, 26, 11339–11372. [Google Scholar] [CrossRef]
  17. Ji, C.; Zhang, Z.; Cheng, G.; Kong, M.; Li, R. A Convex Optimization Method to Time-Optimal Trajectory Planning with Jerk Constraint for Industrial Robotic Manipulators. IEEE Trans. Autom. Sci. Eng. 2023, 21, 7629–7646. [Google Scholar] [CrossRef]
  18. Li, X.; Wang, L.; An, Y.; Huang, Q.-L.; Cui, Y.-H.; Hu, H.-S. Dynamic path planning of mobile robots using adaptive dynamic programming. Expert Syst. Appl. 2024, 235, 121112. [Google Scholar] [CrossRef]
  19. Kaserer, D.; Gattringer, H.; Mueller, A. Time Optimal Motion Planning and Admittance Control for Cooperative Grasping. IEEE Rob. Autom. Lett. 2020, 5, 2216–2223. [Google Scholar] [CrossRef]
  20. Ma, J.-w.; Gao, S.; Yan, H.-t.; Lv, Q.; Hu, G.-q. A new approach to time-optimal trajectory planning with torque and jerk limits for robot. Rob. Auton. Syst. 2021, 140, 103744. [Google Scholar] [CrossRef]
  21. Cui, L.; Wang, H.; Chen, W. Trajectory planning of a spatial flexible manipulator for vibration suppression. Rob. Auton. Syst. 2020, 123, 103316. [Google Scholar] [CrossRef]
  22. Zhang, S.; Dai, S.; Zanchettin, A.M.; Villa, R. Trajectory planning based on non-convex global optimization for serial manipulators. Appl. Math. Modell. 2020, 84, 89–105. [Google Scholar] [CrossRef]
  23. Liu, H.; Lai, X.; Wu, W. Time-optimal and jerk-continuous trajectory planning for robot manipulators with kinematic constraints. Rob. Comput. Integr. Manuf. 2013, 29, 309–317. [Google Scholar] [CrossRef]
  24. Wang, Z.; Li, Y.; Sun, P.; Luo, Y.; Chen, B.; Zhu, W. A multi-objective approach for the trajectory planning of a 7-DOF serial-parallel hybrid humanoid arm. Mech. Mach. Theory 2021, 165, 104423. [Google Scholar] [CrossRef]
  25. Sun, T.; Song, Y.M.; Dong, G.; Lian, B.B.; Liu, J.P. Optimal design of a parallel mechanism with three rotational degrees of freedom. Rob. Comput. Integr. Manuf. 2012, 28, 500–508. [Google Scholar] [CrossRef]
  26. Ma, X.; Shen, W. Generalized de Boor-Cox Formulas and Pyramids for Multi-Degree Spline Basis Functions. Mathematics 2023, 11, 367. [Google Scholar] [CrossRef]
  27. Briot, S.; Arakelian, V.; Le Baron, J.P. Shaking force minimization of high-speed robots via centre of mass acceleration control. Mech. Mach. Theory 2012, 57, 1–12. [Google Scholar] [CrossRef]
  28. Li, X.; Zhao, H.; He, X.; Ding, H. A novel cartesian trajectory planning method by using triple NURBS curves for industrial robots. Rob. Comput. Integr. Manuf. 2023, 83, 102576. [Google Scholar] [CrossRef]
Figure 1. The 5PUS-RPUR virtual prototype and mechanism diagram: (a) virtual prototype; (b) mechanism diagram.
Figure 1. The 5PUS-RPUR virtual prototype and mechanism diagram: (a) virtual prototype; (b) mechanism diagram.
Applsci 15 09212 g001
Figure 2. Coordinate system of the RPUR chain.
Figure 2. Coordinate system of the RPUR chain.
Applsci 15 09212 g002
Figure 3. The scheme of discrete multi-objective planning.
Figure 3. The scheme of discrete multi-objective planning.
Applsci 15 09212 g003
Figure 4. Labeling rule of the discrete cell.
Figure 4. Labeling rule of the discrete cell.
Applsci 15 09212 g004
Figure 5. Rules for discrete position cell paths.
Figure 5. Rules for discrete position cell paths.
Applsci 15 09212 g005
Figure 6. The flowchart of the Dijkstra algorithm.
Figure 6. The flowchart of the Dijkstra algorithm.
Applsci 15 09212 g006
Figure 7. Position fitting trajectory.
Figure 7. Position fitting trajectory.
Applsci 15 09212 g007
Figure 8. The discrete positional diagram of the optimized moving platform: (a) position path curve; (b) posture path curve.
Figure 8. The discrete positional diagram of the optimized moving platform: (a) position path curve; (b) posture path curve.
Applsci 15 09212 g008
Figure 9. Joint drive speed trajectory curve.
Figure 9. Joint drive speed trajectory curve.
Applsci 15 09212 g009
Figure 10. Acceleration trajectory curve of each actuator joint.
Figure 10. Acceleration trajectory curve of each actuator joint.
Applsci 15 09212 g010
Figure 11. Displacement curve of the actuated joints from four different algorithms.
Figure 11. Displacement curve of the actuated joints from four different algorithms.
Applsci 15 09212 g011
Figure 12. The comparison chart of acceleration fluctuation value.
Figure 12. The comparison chart of acceleration fluctuation value.
Applsci 15 09212 g012
Table 1. The dimension parameters of the 5PUS-RPUR parallel robot.
Table 1. The dimension parameters of the 5PUS-RPUR parallel robot.
SymbolValue (Unit)
l10.119 m
l20.268 m
r0.343 m
R0.100 m
λ30°
a10.121 m
a20.119 m
a30.102 m
Table 2. Time intervals of the points with 2.37 s.
Table 2. Time intervals of the points with 2.37 s.
Intervals No.t1t2t3t4t5t6t7t8t9t10
Time interval0.5280.3270.260.2090.1580.1230.0810.1370.230.317
Table 3. RMS values of actuated joint displacement difference for four different algorithms.
Table 3. RMS values of actuated joint displacement difference for four different algorithms.
MethodPMTNCCCSFP
Actuator Variable
θ10.001600.001690.001710.00239
θ20.0002480.0002600.0002420.000365
θ30.0007580.0007700.0009520.00104
θ40.001120.0011630.001390.00161
θ50.002910.003070.003150.00434
θ60.0009470.0009940.001090.00140
Table 4. Comparison of online computation time for different methods.
Table 4. Comparison of online computation time for different methods.
MethodDescriptionOnline Computation Time (ms)
PMB-spline + GA14.5
FMFifth-order Polynomial3.3
TNCTriple NURBS + GA14.3
CCSCubic & Septuple B-spline + SQP13.8
Note: Times are averaged over 10 runs.
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Luo, Y.; Li, S.; Ruan, J.; Bai, J. A Space Discretization Method for Smooth Trajectory Planning of a 5PUS-RPUR Parallel Robot. Appl. Sci. 2025, 15, 9212. https://doi.org/10.3390/app15169212

AMA Style

Luo Y, Li S, Ruan J, Bai J. A Space Discretization Method for Smooth Trajectory Planning of a 5PUS-RPUR Parallel Robot. Applied Sciences. 2025; 15(16):9212. https://doi.org/10.3390/app15169212

Chicago/Turabian Style

Luo, Yiqin, Sheng Li, Jian Ruan, and Jiping Bai. 2025. "A Space Discretization Method for Smooth Trajectory Planning of a 5PUS-RPUR Parallel Robot" Applied Sciences 15, no. 16: 9212. https://doi.org/10.3390/app15169212

APA Style

Luo, Y., Li, S., Ruan, J., & Bai, J. (2025). A Space Discretization Method for Smooth Trajectory Planning of a 5PUS-RPUR Parallel Robot. Applied Sciences, 15(16), 9212. https://doi.org/10.3390/app15169212

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop