Next Article in Journal
On the Classification of Totally Geodesic and Parallel Hypersurfaces of the Lie Group Nil4
Previous Article in Journal
Symmetry-Preserving Federated Learning with Blockchain-Based Incentive Mechanisms for Decentralized AI Networks
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

An Inverse Kinematics Solution for Mobile Manipulators in Textile Workshops Based on an Improved Particle Swarm Optimization

1
School of Information Science and Engineering, Harbin Institute of Technology at WeiHai, Weihai 264209, China
2
School of Ocean Engineering, Harbin Institute of Technology at Weihai, Weihai 264209, China
*
Author to whom correspondence should be addressed.
Symmetry 2025, 17(11), 1980; https://doi.org/10.3390/sym17111980
Submission received: 22 October 2025 / Revised: 13 November 2025 / Accepted: 14 November 2025 / Published: 16 November 2025

Abstract

To enhance the operational performance of mobile manipulators in textile workshops and address the difficulty of inverse kinematics (IK) for this class of redundant manipulators, this paper leverages the robot’s structural symmetries and proposes a chaotic-mutation particle swarm optimization (CMPSO)-based IK algorithm for mobile manipulators, thus simplifying the solution process and ensuring balanced exploration of the search space. First, the coordinate–transformation relationships of the mobile manipulator are analyzed to establish its forward kinematic model. Then, a multi-objective constrained IK model is formulated according to the manipulator’s operating characteristics. The model incorporates a pose-error function, the ‘compliance’ principle, and joint-limit avoidance. To solve this model accurately, we refine the population initialization and boundary-violation handling of the particle swarm algorithm and introduce an asymmetric mechanism via an adaptive mutation strategy, culminating in a CMPSO-based IK solver. On this basis, single-pose IK tests and trajectory-planning experiments are conducted, and simulation results verify the effectiveness and stability of the proposed algorithm.

1. Introduction

With advances in science and technology and growing production demands, the industrial sector is entering a new era—Industry 4.0 [1]. As a traditional manufacturing sector, the textile industry is also experiencing a transformation towards automation and informatization. However, the contemporary textile industry is confronted with challenges such as overcapacity and intense competition, which necessitate the development of smart textile factories as a pivotal pathway for its transformation [2]. The introduction of intelligent equipment such as mobile manipulators in processes like transportation and spinning in textile factories not only reduces labor costs and enhances productivity but also helps to ensure product quality, playing a significant role in the intelligent transformation of textile factories [3].
In recent years, symmetry has assumed an increasingly important role in the modeling and control of robotic systems. Many redundant robots—particularly mobile manipulators—employ asymmetric mechanical architectures to enhance operational flexibility. Mobile manipulators combine the planar mobility of a mobile base with the precise operational capabilities of a multi-degree-of-freedom manipulator, greatly expanding the workspace and adapting to the complex and dynamic environments in textile factories. The study of inverse kinematics for manipulators involves, given a desired end-effector pose, calculating the joint angles of the manipulator. Such problems are often computationally intensive, have non-unique solutions, and require optimization of the results [4]. However, incorporating a mobile base introduces nonholonomic constraints and additional redundant degrees of freedom. This substantially increases model complexity and makes the inverse kinematics problem more challenging [5]. Thus, how to accurately and efficiently solve the inverse kinematics of mobile manipulators has become an important research topic in the field of robotics.
R. Raja et al. proposed an improved KSOM learning framework to learn the mapping between the joint angle space and Cartesian space, addressing the inverse kinematics problem of mobile manipulators and maximizing the operability of the manipulator during the solution process [6]. Khan et al. transformed the tracking problem of mobile manipulators into a constrained position-level optimization problem and employed an improved recurrent neural network algorithm to solve the inverse kinematics under nonholonomic constraints, verifying the stability and convergence of the algorithm [7]. Zhao et al., by integrating task space constraints, joint limit constraints, and collision-free constraints with obstacles, proposed a novel algorithm based on Newton’s method and first-order techniques to generate collision-free inverse kinematics solutions, achieving dynamic obstacle avoidance for spherical obstacles [8]. Abbireddy et al. formulated the IK problem of a redundant manipulator as a nonlinear constrained optimization problem, whose objective is to minimize the position and orientation errors while avoiding obstacles. The classical nonlinear optimization method SQP, together with obstacle-avoidance techniques, was employed to determine the joint variables, and a bounding-box-based method was used to achieve collision avoidance [9]. Zhang et al. introduced a fast solving framework for mobile manipulators with unique domain constraints, along with a real-time obstacle avoidance strategy for the manipulator [10]. Li et al. introduced six parameters to characterize the motion redundancy and transformed the inverse kinematics of dual mobile manipulators into a non-redundant inverse kinematics problem. Subsequently, a weighted product form of normalized ideal redundant behaviors was constructed as the objective function. Finally, the Nelder–Mead simplex method was employed to optimize the redundancy parameters, thereby obtaining the desired joint configuration [11]. Jin et al. treated the mobile base and the manipulator as an integrated system and designed a fully connected network (FCN) to predict the positions and joint configurations of all degrees of freedom based on the target pose, achieving an online optimization for the whole-body inverse kinematics of the mobile manipulator. However, compared to the commonly used NNO algorithm, this method requires a longer computation time and its optimization speed needs improvement [12]. Xu et al. simplifies the inverse kinematics problem of the nine-axis gantry robot into that of a six-axis robotic arm. Through simulation experiments and specific experiments on the Staubli RX160L robotic arm, the accuracy of the inverse kinematics analysis of the robot was confirmed [13]. However, the aforementioned algorithms often rely on complex computations or extensive data training, thereby increasing the cost of solving the inverse kinematics. In response to these shortcomings, an increasing number of researchers have begun to employ intelligent optimization algorithms that do not rely on data training and have lower computational complexity to solve the inverse kinematics problem of mobile manipulators. Algorithms such as Differential Evolution [14], Fruit Fly Optimization [15], Artificial Fish Swarm Algorithm [16], Particle Swarm Optimization [17] and Bald Eagle Search Optimization Algorithm [18] have all been validated for their effectiveness in solving these problems.
Among the intelligent optimization algorithms previously referenced, Particle Swarm Optimization is distinguished by its simple structure and ease of implementation, and is frequently employed to solve complex constrained problems. It has been extensively applied to the inverse kinematics problem of mobile manipulators. Ram et al., targeting mobile manipulators in complex environments, formulated a multi-objective optimization problem with objectives of minimizing pose error and total joint movement, and with obstacle avoidance as a constraint, thereby achieving joint decoupling and an inverse kinematics solution for the mobile manipulator [19]. For SSRMS-type redundant manipulators, Jin et al. introduced the elbow joint posture and derived the algebraic relationship between the elbow posture and joint angles. By incorporating obstacle avoidance and singularity avoidance as additional tasks to constrain the particle swarm algorithm, the approach demonstrated satisfactory performance in terms of accuracy, efficiency, and operability, although it did not account for joint limit issues [20]. Liu et al., for general manipulators that do not satisfy the Pieper criterion, employed an improved particle swarm algorithm to solve their inverse kinematics. They introduced a nonlinear dynamic inertia weight adjustment method based on the concept of similarity and simultaneously utilized multiple populations for the search, thereby enhancing the stability of the inverse solution [21]. Cao et al. presents an improved quantum particle swarm optimization algorithm (IQPSO), which is used to solve the inverse kinematics problems. In this algorithm, quantum behavior is added to the particle swarm optimization algorithm, improve the convergence speed and solution accuracy [22]. Ning et al. proposed an adaptive transfer particle swarm algorithm (VDMAT-PSO) based on measures of velocity and directional manipulability, providing a solution for the inverse kinematics of mobile manipulators [23]. These approaches demonstrate the effectiveness of PSO-based solvers, but each focuses on specific aspects of performance. Challenges such as ensuring a well-distributed search in the high-dimensional solution space and avoiding premature convergence remain unsolved in many cases. In particular, no prior work has integrated multiple advanced PSO strategies into a unified solver for the IK problem of mobile manipulators. This gap means that existing methods may still suffer from uneven exploration of the redundant solution space or early stagnation in local optima.
In recent years, researchers have increasingly leveraged system symmetry in kinematic modeling, controller architectures, and optimization algorithms to simplify computation and improve performance. Correspondingly, deliberately introduced asymmetries—such as nonuniform gains or perturbations in control strategies—have become a growing trend for enhancing robustness and adaptability. By jointly exploiting symmetry and asymmetry in algorithmic and control design, robotic systems achieve improved stability and performance in complex, uncertain environments. To address the limitations of PSO solvers mentioned above, we propose a targeted integrated optimization strategy for IK, which combines several techniques in a novel way. We refer to this improved algorithm as Chaotic Mutation PSO (CMPSO). The integration of these three strategies is specifically designed to balance solution-set distribution and convergence quality in the redundant, high-dimensional search space of a mobile manipulator. We highlight the synergy of the integrated strategies: Sobol initialization ensures a high-quality, uniformly distributed starting population. The logistic chaotic perturbation introduces asymmetry in the swarm’s evolution, preventing synchronized premature convergence by re-diversifying particles when they approach boundaries. The Gaussian–Cauchy mutation adaptively balances local fine-tuning and global exploration, helping particles escape local optima while maintaining convergence precision. Together, these mechanisms complement each other to significantly improve the algorithm’s global search ability, population diversity, and solution accuracy. We apply the proposed CMPSO to a 9-DOF mobile manipulator’s IK problem and conduct extensive simulations, including single-point IK solving and continuous trajectory planning. Comparative experiments against the standard PSO and other enhanced variants demonstrate that our integrated approach achieves superior accuracy, stability, and efficiency.

2. Materials and Methods

2.1. Problem Description of the Inverse Kinematics for Mobile Manipulators

Due to the combination of a mobile platform and a robotic arm, mobile manipulators exhibit highly redundant degrees of freedom, and the relationship between structural symmetry and redundancy cannot be overlooked. Mobile manipulators typically adopt asymmetric configurations; for example, coupling a six-DOF arm with a symmetrically distributed joint layout to a two-wheel chassis yields multiple equivalent inverse solutions for a given end-effector pose. This multiplicity arising from structural asymmetry highlights the presence of redundancy: an asymmetric mechanical architecture allows the manipulator to reach the same end-effector pose via different joint combinations. This redundancy increases motion flexibility but also requires extra constraints to obtain a unique solution.
In our fitness-function design, asymmetric constraints are introduced to select the preferred inverse-kinematics (IK) solution. On the one hand, following the “compliance” principle, candidate solutions are evaluated to favor configurations in which joints stay away from singular postures and the overall posture is relaxed and well conditioned; on the other hand, a joint-limit-avoidance penalty is added to reduce the fitness of solutions whose joint angles approach their admissible bounds. By embedding these asymmetric constraints into the fitness function, we break the equivalence among the multiple solutions induced by the asymmetric structure and, while maintaining end-effector positioning accuracy, prioritize IK solutions that satisfy compliance and safety requirements, thereby improving the robustness of motion planning in redundant systems.

2.1.1. Mobile Manipulator Forward Kinematics

The mobile manipulator studied in this paper consists of a mobile base with three planar degrees of freedom and an Elite collaborative manipulator with six spatial degrees of freedom; its three-dimensional model is shown in Figure 1. The manipulator is rigidly mounted on the mobile base, and no relative motion exists between the manipulator base and the mobile platform. The end-effector is equipped with a gripper to perform pick-and-place tasks in the textile workshop.
Since the floor in a textile workshop is almost flat, it can be assumed that the wheels of the mobile base always remain perpendicular to the ground. The mobile base thus possesses three planar degrees of freedom relative to the world coordinate system, which are the x-axis coordinates x p , the y-axis coordinates y p , and the direction of the mobile base α p . Accordingly, the homogeneous transformation matrix of the mobile base coordinate system Σ p with respect to the world coordinate system Σ w is given by T p w .
T p w = cos α p sin α p 0 x p sin α p cos α p 0 y p 0 0 1 0 0 0 0 1
The distances between the installation point of the manipulator base and the center of the mobile base along three specified directions are d x , d y and d z respectively. As there is no relative motion between the manipulator base and the mobile base, the homogeneous transformation matrix T m p of the manipulator base coordinate system Σ m with respect to the mobile base coordinate system Σ p is expressed as:
T m p = 1 0 0 d x 0 1 0 d y 0 0 1 d z 0 0 0 1
The kinematic model of the Elite robotic arm is established using the Modified Denavit–Hartenberg (MD-H) coordinate representation. For the links connected by rotational joints, the relationship between the adjacent coordinate systems at any given position is shown in Figure 2. In the figure, a i represents the link length, α i represents the link twist angle, d i represents the link offset, and θ i represents the link angle.
The joint coordinate allocation of the Elite manipulator is shown in Figure 3.
Thus, the D–H parameter table for the Elite manipulator is presented in Table 1.
By combining Figure 2 and Table 1, and based on the transformation relationships between the links, the transformation matrix T i i 1 between two adjacent links can be constructed as:
T i i 1 = T r a n s a i 1 , 0 , 0 R o t X i 1 , α i 1 T r a n s 0 , 0 , d i R o t Z i , θ i = c θ i s θ i 0 a i 1 s θ i c α i 1 c θ i c α i 1 s α i 1 d i s α i 1 s θ i s α i 1 c θ i s α i 1 c α i 1 d i c α i 1 0 0 0 1
where s θ i represents sin θ i , c θ i represents cos θ i , s α i 1 represents sin α i 1 , c α i 1 represents cos α i 1 .
Consequently, the homogeneous transformation matrix T t m of the tool coordinate system Σ t with respect to the manipulator base coordinate system Σ m is given by
T t m = T 1 0 T 2 1 T 3 2 T 4 3 T 5 4 T 6 5
According to the chain rule, the forward kinematics of the mobile manipulator in the textile workshop can be expressed as:
T t w = T p w T m p T t m = r 11 r 12 r 13 p 1 r 21 r 22 r 23 p 2 r 31 r 32 r 33 p 3 0 0 0 1
where r i j ( i , j = 1 , 2 , 3 ) is the rotation matrix representing the orientation transformation of the end-effector with respect to the world coordinate system, and p k k = 1 , 2 , 3 is the position vector representing the position transformation of the end-effector with respect to the world coordinate system.

2.1.2. Inverse Kinematics for the Mobile Manipulator

Define the generalized degrees of freedom of the mobile manipulator as:
X * = x p *     y p *     α p *     θ 1 *     θ 2 *     θ 3 *     θ 4 *     θ 5 *     θ 6 *
From the forward kinematics in Section 2.1.1, the inverse kinematics problem for the mobile manipulator is to find a set of joint variables X * such that its forward kinematics meets the requirements of Equation (5). The fitness function based on orientation error and position error is defined as the sum of the square of the Frobenius norm of the orientation matrix error and the square of the 2-norm of the position error vector:
f 1 = i = 1 3 j = 1 3 ( r i j r i j , t a r ) 2 + k = 1 3 ( p k p k , t a r ) 2
Here, r i j and r i j , t a r denote the actual and desired orientation matrices of the mobile manipulator, respectively, p k and p k , t a r denote the corresponding position vectors of the mobile manipulator. To obtain a high-precision pose, the value of the fitness function should be as small as possible.
However, as a manipulator with redundant degrees of freedom, the mobile manipulator generally has multiple inverse kinematics solutions for a given end-effector pose in the world coordinate system. Therefore, constraints are necessary in the solving process to obtain an optimal solution. By introducing the “pliancy” principle into the inverse kinematics formulation, the fitness function is modified to ensure that the solution also minimizes energy consumption of the mobile manipulator. The pliancy principle guarantees that during the transition from the current pose to the desired pose, the joints closer to the manipulator base move as little as possible while the joints farther away move more, thus achieving the goal of reducing energy consumption in joints. For the mobile manipulator used in this paper, assuming the initial generalized joint configuration is X i n i t , a “pliancy principle”-based objective function is established as:
f 2 = ( x p * x p , i n i t ) 2 + ( y p * y p , i n i t ) 2 + ( α p * α p , i n i t ) 2 + i = 1 6 ω i ( θ i * θ i , i n i t ) 2
where the weighting coefficient ω i for the i -th joint is positive and larger for joints near the base and smaller for joints farther away. To minimize joint motion and energy consumption during mobile manipulator operation, the value of the objective function should be minimized.
In addition, if any joint angle nears its limit during motion, the stiffness of the manipulator may deteriorate, thereby affecting subsequent trajectory tracking. Thus, an objective function based on joint limit avoidance is defined to further constrain the solution:
f 3 = i = 1 6 1 γ ( θ max , i θ min , i ) 2 ( θ max , i θ i ) θ i θ min , i
Here, θ max , i represents the upper limit of the motion range for the i -th joint of the robotic arm, θ min , i represents the lower limit of the motion range for the i -th joint, and γ is a positive scalar gain. To ensure that the joints of the manipulator remain as close as possible to the middle value of their motion range, the value of the obtained solution f 3 should be minimized.
Based on the above constraints, the final fitness function of the inverse kinematics model for the mobile manipulator is expressed as:
F = λ 1 f 1 + λ 2 f 2 + λ 3 f 3 , i = 1 3 λ i = 1 x i , min x i x i , max

2.2. Chaotic Mutation Particle Swarm Optimization

2.2.1. Basic Principles of Particle Swarm Optimization

Particle Swarm Optimization (PSO) was originally proposed by Kennedy and Eberhart [24]. It simulates the flocking behavior of birds, where each particle represents a potential solution flying through the search space. In PSO, a fitness function is used to evaluate the quality of each solution, and every particle has an associated fitness value. Once the population is initialized, particles begin to search the flying space by following the current best particle. During the iterative process, particles update themselves primarily by tracking two extreme values: the individual best (the best solution each particle has found so far) and the global best (the best solution found by any particle in the population). In some PSO variants, a subset of particles is chosen as neighbors, and the best solution found among these is referred to as the local best.
For a D-dimensional optimization problem, assume the population size is N; each particle thus exists in a D-dimensional space. Let the following vectors be defined:
  • The position of a particle at time t is represented as a D-dimensional vector:
    X i t = ( x i 1 t , x i 2 t , , x i D t ) T , i = 1 , 2 , 3 N ;
    where x i d t l b , u b , with the lower and upper bounds for the d-th dimension being l b , u b respectively.
  • The velocity of a particle at time t is represented as a D-dimensional vector:
    V i t = ( v i 1 t , v i 2 t , , v i D t ) T , i = 1 , 2 , 3 N ;
    where v i d t V m a x , d , V m i n , d , V m a x , d ,   V m i n , d are the maximum and minimum velocity of the particle respectively.
  • The individual best solution encountered by each particle so far is denoted as:
    P i b e s t t = ( p i 1 t , p i 2 t , , p i D t ) T ;
  • The global best solution found by the entire swarm is denoted as:
    P g b e s t t = ( p g 1 t , p g 2 t , , p g D t ) T ;
After initializing the swarm, the PSO algorithm iteratively updates the particles. In each iteration, the particles determine their individual and global bests based on their fitness values and update their velocities and positions according to the following equations:
V i d t + 1 = ω i V i d t + c 1 r 1 p i d t x i d t + c 2 r 2 p g d t x i d t
x i d t + 1 = x i d t + V i d t + 1
In Equation (11), the inertia weight ω i determines the influence of the particle’s velocity at time t. A larger ω i strengthens the global search ability of the algorithm while weakening its local search capability, leading to faster convergence but lower solution accuracy. Conversely, a smaller ω i enhances the local search ability and improves accuracy, but makes it more difficult for the algorithm to escape local optima. In this study, a linear decreasing inertia weight (LDW) strategy is adopted, which is expressed as follows:
ω = ω max ω max ω min T T max
In Equation (13), ω max represents the initial value of the inertia weight, which is also its maximum value, typically set to 0.9; ω min denotes the final value of the inertia weight, which is its minimum value, typically set to 0.2. In this way, the inertia weight linearly decreases from 0.9 to 0.2 during the iterations, significantly enhancing the optimization performance of the algorithm. In Equation (11), c 1 and c 2 are acceleration coefficients (also called learning factors) that indicate the weights of the individual and global best influences. Smaller coefficients allow particles to wander near the target region, while larger coefficients can cause sudden movements toward or away from the target; hence, excessively large or small coefficients are detrimental to the search, and typical values are chosen as c 1 = c 2 = 2 . The random numbers r 1 and r 2 are uniformly distributed in the interval [ 0 ,   1 ] .

2.2.2. Uniform Particle Swarm Optimization Based on Chaotic Mapping and Mutation

Although PSO is favored in academia for its simple structure and ease of implementation across various optimization problems, deeper research has revealed that it suffers from premature convergence, low precision, and a tendency to fall into local optima [25]. To address the foregoing issues, we propose a chaotic-mutation particle swarm optimization (CMPSO) algorithm that fuses symmetric and asymmetric design principles. First, during population initialization we adopt a uniform-distribution strategy to achieve as even, symmetric coverage of the search space as possible. This symmetric population layout helps avoid search bias, ensures that regions near the global optimum are not overlooked, and thereby improves the quality of the algorithm’s starting point for global optimization. Subsequently, we perturb the swarm with a logistic-map–based chaotic sequence and, together with an adaptive mutation mechanism, randomly adjust particle velocities and positions. Compared with the near-synchronous convergence typical of standard PSO, this chaotic perturbation and mutation act as an asymmetric stochastic excitation: they disrupt symmetric convergence patterns that may emerge during evolution, drive a subset of particles to escape local minima in a nonuniform manner, and enhance global exploration. By combining symmetric uniform initialization with an asymmetric chaotic-mutation strategy, the algorithm maintains population diversity while accelerating convergence, significantly improving the robustness and efficiency of IK computation.
  • Population Initialization Based on Sobol Sequences
In PSO, the initial distribution of particles significantly influences the final accuracy and convergence of the algorithm. For the inverse kinematics problem of the mobile manipulator—which is characterized by a large search space and high dimensionality—the initial particles should be uniformly distributed within the search space to enhance diversity and ensure that the global optimum can be located. Traditional PSO methods generate the initial population using pseudo-random numbers, which tend to have low uniformity and may lower both the search efficiency and solution precision.
In contrast to the sequences of pseudo-random numbers, the Quasi-Monte Carlo (QMC) method uses deterministic low-discrepancy sequences (also called quasi-random or sub-random sequences) instead of pseudo-random sequences [26]. The Sobol sequence is a typical low-discrepancy sequence and, compared with pseudo-random numbers, distributes points more evenly within the unit hypercube. This property makes it more efficient in exploring the search space in numerical integration, global optimization, and Monte Carlo simulation problems. Figure 4 compares sample points generated by pseudo-random sequences and Sobol sequences in a two-dimensional space, clearly illustrating that the Sobol sequence provides more comprehensive coverage.
In this paper, the Sobol sequence is employed to generate the initial population. Suppose the search boundaries for a particle are given as [ l b , u b ] , the Sobol-generated points u [ 0 , 1 ] , then the position of the initial population of particles can be mapped to:
x = l b + ( u b l b ) × u
This mapping translates the uniform distribution within the unit hypercube to the actual search space, ensuring that the population covers the entire search interval at initialization. Although the Sobol sequence inherently has low discrepancy, in high-dimensional problems it may exhibit structural regularity leading to insufficient sampling in certain areas. Therefore, a random perturbation is added to break the structure, thereby providing a more random yet low-discrepancy initial population.
2.
Boundary Handling Based on the Logistic Map
In standard PSO, when particles exceed the search boundaries, a simple method is used where the boundary value is assigned to the out-of-bound particle’s position or velocity. Although this method is straightforward, it often diminishes the performance of the particle in subsequent searches and may cause the algorithm to get trapped in local optima. Owing to the inherent randomness and ergodicity of chaotic maps, this paper utilizes the Logistic map to regenerate the positions of out-of-bound particles instead of simply truncating them to the boundary, thereby preserving the particle’s search capability. The Logistic map was first proposed by May [27], and its chaotic mapping equation is given by:
x n + 1 = r × x n × ( 1 x n )
In Equation (15), x n [ 0 , 1 ] , n is the number of chaotic mapping iterations, and r [ 0 , 4 ] is the chaotic coefficient. When 3.5699456 r 4 , Logistic map is in a chaotic state; when the chaotic coefficient is close to 4 the map behaves like a pseudo-random sequence; for lower values, the function converges to a fixed point. In this paper, out-of-bound particles are remapped back into the feasible domain using the Logistic map, avoiding the loss of population diversity that a simple boundary truncation might cause. The implementation procedure is as follows:
  • Record the particle’s position in the dimensions where it exceeds the boundary x i d ;
  • Map the out-of-bound position x i d into the interval [ 0 , 1 ] by Equation (16), where l b , u b are the lower and upper bounds;
    x i d 0 = x i d l b u b l b , x i d l b < u b l b u b l b x i d l b , x i d l b u b l b
  • According to Equation (15) iteration n times to get x i d n ;
  • Use the inverse operation of Equation (16) to place the chaotic state particle back into the solution space;
  • Evaluate the fitness of the remapped particle to determine whether to update its individual best.
3.
Adaptive Mutation Strategy for Particles
In standard PSO, as the particles converge toward the global best, the swarm tends to lose diversity and becomes prone to local optima. To increase diversity and enhance the search ability in later stages, this paper designs a selective adaptive weighted mutation strategy: for particles with fitness values worse than the population average, weighted Cauchy mutation and Gaussian mutation are applied, with the mutation weight depending on the fitness of the particle.
Gaussian mutation utilizes normally distributed random numbers to perturb the particle’s position. Due to the property of the normal distribution where most values are concentrated around the mean and the probability density quickly decreases with distance, Gaussian mutation typically results in small perturbations, aiding in local search and fine-tuning. The Gaussian mutation is defined as Equation (17):
x g u a s s i a n = p i b e s t + N ( 0 , 1 )
Gaussian mutation has good local search capabilities but is not effective in helping particles escape from local optima. Therefore, Cauchy mutation—with its heavy-tailed characteristics—is also introduced. Cauchy mutation, based on the Cauchy distribution, can not only generate small disturbances but also has a higher probability of generating larger perturbations, facilitating global search. The Cauchy mutation is defined as Equation (18):
x c a u c h y = p i b e s t + C a u c h y 0 , 1
After mutation, the new position of a particle is given by:
x m u t a t i o n = ( 1 γ ) × x g a u s s i a n + γ × x c a u c h y
where γ [ 0 , 1 ] is the adaptive mutation factor calculated by:
γ = i = 1 N q i t N q i t = 1 , f ( P i b e s t t ) < f P i b e s t t 1 0 , f ( P i b e s t t ) f P i b e s t t 1
In the early stages of the algorithm, γ is large so that inferior particles are more likely to undergo Cauchy mutation, thereby expanding the search space and enhancing the algorithm’s ability to perform wide-range exploration in the initial phase; in later stages, as γ approaches zero, the algorithm has already converged near the global optimum. At this stage, inferior particles are more likely to undergo Gaussian mutation, which strengthens the local search capability of the particles. This fitness-based weighted mutation method thus increases population diversity and improves overall performance.

2.2.3. Algorithm Flow of the Chaotic Mutation Particle Swarm for Inverse Kinematics

For the inverse kinematics model described in Section 2.2.2, each particle is composed of 9 joint variables, its position vector is defined as X i = x p i     y p i     α p i     θ 1 i     θ 2 i     θ 3 i     θ 4 i     θ 5 i     θ 6 i , its velocity vector is defined as V i = v 1 i     v 2 i     v 3 i     v 4 i     v 5 i     v 6 i     v 7 i     v 8 i     v 9 i , with each position vector representing one feasible inverse kinematics solution.
Based on the above strategies, the main steps of the chaotic mutation particle swarm algorithm (CMPSO) for solving the inverse kinematics are as follows:
  • Algorithm Initialization: Set the population size N , maximum number of iterations T , problem dimension D , learning factors c 1 , c 2 , the velocity boundaries V m i n , d , V m a x , d , the position boundaries L d , U d .
  • Initial State: Generate a uniformly distributed initial population using the Sobol sequence as described in Equation (14) and calculate the fitness value for each particle. Store each particle’s initial position and fitness value in vector P i b e s t , and record the particle with the best fitness value as the initial global best in P g b e s t .
  • State Update: Update the velocity and position of each particle using Equations (11) and (12) and check for boundary violations. If a particle’s position exceeds the boundaries, remap the particle back into the search space using Equations (15) and (16).
  • Evaluation and Mutation: Compute the fitness value for each particle in the current iteration and compare it with the individual best fitness value. If the current fitness is better, update P i b e s t accordingly. For those particles whose fitness is worse than the population average, apply the adaptive weighted mutation as given in Equation (19) and evaluate whether an update of P i b e s t is necessary.
  • Swarm Update: Compare the individual best fitness values with the global best. If an individual value is superior, update the global best P g b e s t accordingly.
  • Termination Check: Determine whether the maximum number of iterations has been reached. If so, terminate the algorithm; otherwise, proceed to the next iteration starting from step (3) until T is reached.
  • Output: Return the optimal solution P g b e s t of the fitness function.

3. Simulation and Results

All experiments in this study were conducted on a computer running Windows 11 and equipped with a 13th Gen Intel® Core™ i7-13620H processor (Intel Corporation, Santa Clara, CA, USA) at 2.40 GHz. Python 3.13.0 was used as the simulation environment. Inverse kinematics tests were performed for both single-point and continuous-point cases.

3.1. Single-Point Inverse Kinematics Ablation Experiment

To thoroughly verify the effectiveness of the CMPSO improvement strategies, ablation experiments are first conducted. For the mobile manipulator in the textile workshop shown in Figure 1, ablation tests of inverse kinematics based on the chaotic-mutated particle swarm optimization algorithm are performed following the algorithm flow described in Section 2.2.3. The specific procedure is as follows: given the desired end-effector pose and the initial pose of the mobile manipulator, the improvement strategies of CMPSO are removed individually, and the nine joint variables of the mobile manipulator are solved accordingly. The obtained joint solutions are then substituted into the forward kinematics to compute the actual end-effector pose, and the error relative to the desired pose is evaluated. The algorithm parameters are set as follows: the maximum number of iterations is T = 500, and the population size is N = 30; the extrema of the inertia weight are ω max = 0.9 and ω min = 0.2 ; acceleration coefficients c 1 = c 2 = 2 ; to ensure that the particles remain in a fully chaotic state, the chaotic coefficient is chosen as r = 4. The initial configuration of the mobile manipulator is set as:
X 0 = [ 0     0     0     0     p i / 2     0     0     p i / 2     0 ] T
The desired homogeneous transformation matrix corresponding to the end-effector is given by:
T target = r 11 , t a r r 12 , t a r r 13 , t a r x t a r r 21 , t a r r 22 , t a r r 23 , t a r y t a r r 31 , t a r r 32 , t a r r 33 , t a r z t a r 0 0 0 1 = 0.9998 0.0183 0.0091 0.5000 0.0184 0.9997 0.0137 0.5000 0.0089 0.0139 0.9999 0.4000 0 0 0 1.0000
The position error for the single-point inverse kinematics solution is defined as:
E p o s = ( x p x target ) 2 + ( y p y target ) 2 + ( z p z target ) 2
and the orientation error is defined as:
E o r i = i = 1 3 j = 1 3 ( r i j r i j , t a r ) 2
  • Ablation Experiment on Population Initialization Method
In this experiment, the Sobol sequence-based population initialization method in CMPSO was removed. The convergence curves of the fitness values are shown in Figure 5.
It can be observed that the original CMPSO (before removal) exhibits a lower initial fitness value. This is because the Sobol sequence-based initialization distributes particles more uniformly within the feasible domain, resulting in a higher-quality global optimum in the initial state. Moreover, due to this uniformly distributed starting condition, the algorithm is able to converge toward a better solution in the later stages.
2.
Ablation Experiment on Particle Boundary-Handling Strategy
In this experiment, the Logistic mapping-based boundary-handling method in CMPSO was removed. The convergence curves of the fitness values are shown in Figure 6.
It can be observed that when a simple truncation method is used for boundary handling, the algorithm falls into a local optimum during the early and middle stages of iteration and fails to escape. In contrast, the CMPSO algorithm maintains a consistent convergence trend throughout the iterative process. This is because the Logistic mapping-based boundary-handling strategy allows particles that move outside the feasible domain to return uniformly to the feasible region rather than being fixed at the boundary, thereby enhancing their ability to re-explore the search space.
3.
Ablation Experiment on Particle Mutation Strategy
In this experiment, the adaptive mutation strategy of particles was removed. The convergence curves of the fitness values are shown in Figure 7.
It can be observed that CMPSO exhibits more pronounced and frequent stepwise convergence behavior and ultimately finds a better feasible solution. This is because, with the adaptive mutation strategy, particles selectively undergo Gaussian mutation or Cauchy mutation based on their current fitness values, which greatly enhances their ability to escape local optima. As a result, the fitness curve demonstrates stepwise changes. This mutation mechanism significantly improves the search capability of particles, enabling CMPSO to achieve higher solution accuracy in inverse kinematics computation.

3.2. Single-Point Inverse Kinematics Comparison Experiment

The proposed CMPSO is compared with the standard PSO, Adaptive PSO (APSO) [17], and Quantum-behaved PSO (QPSO) [28] in inverse kinematics experiments. The basic algorithm parameters are the same as those in Section 3.1, and the remaining algorithm parameters are set as follows: acceleration coefficient range for APSO as [ 1.5 , 2 ] , and contraction–expansion factors for QPSO as β 1 = 0.5 , β 2 = 1.0 . The convergence curves depicting the variation in the fitness value with iteration are shown in Figure 8.
Analysis of the convergence curves shows that compared with the other three algorithms, CMPSO starts with a lower initial fitness value due to the use of the Sobol sequence for population initialization, which results in a more uniform distribution of particles in the search space. As the iterations proceed, CMPSO converges the fastest and achieves the highest solution accuracy.
Fifty independent runs were conducted for each algorithm, recording the best fitness value, worst fitness value, mean fitness value, fitness variance, and the average pose error. The pose error is defined as E = E o r i + E p o s . The stability of the algorithms was analyzed, and the results are summarized in Table 2.
From Table 2, it can be seen that compared with PSO, APSO, and QPSO, the proposed CMPSO exhibits the smallest mean fitness value and variance, indicating superior stability and convergence, with the average pose error reduced by 70.15%, 54.39%, and 36.05%, respectively. This significantly enhances the accuracy of the inverse kinematics solution.
Inverse kinematics serves as the foundation for subsequent trajectory planning. The time performance of the algorithm determines whether the mobile manipulator can achieve real-time trajectory planning; therefore, it is necessary to evaluate the computational efficiency of the algorithm and further optimize its time complexity when required. According to our previous research, the mobile manipulator studied in this work must operate at a control frequency of at least 250 Hz in the textile workshop. Thus, the solution time of the inverse kinematics algorithm should be less than 4 ms. A total of 1000 inverse kinematics computations were randomly performed within the workspace of the mobile manipulator, and the computation times of the proposed CMPSO as well as PSO, APSO, and QPSO are summarized in Table 3.
As shown in Table 3, the proposed CMPSO-based inverse kinematics algorithm exhibits significantly superior time performance compared with the other three PSO variants in the random experiments. This improvement is attributed to the designed joint-limit-avoidance constraint, which keeps the manipulator joints away from singular configurations, enhances manipulability, and reduces the computational cost of matrix operations. Based on the maximum and average computation times of CMPSO, the proposed inverse kinematics algorithm can almost satisfy a 1 kHz control frequency, which is much higher than the required 250 Hz. Furthermore, the low variance indicates that the computation efficiency of CMPSO is highly stable, fulfilling the requirements of real-time trajectory planning.
We define successful computation as the case in which the solution error converges to within 1% of the desired pose, upon which the algorithm terminates; otherwise, the computation is considered a failure. Similarly, 1000 random solution experiments were conducted within the workspace of the mobile manipulator, and the computation times for successful solutions are summarized in Table 4.
As shown in Table 4, when convergence error rather than iteration count is used as the termination criterion (a criterion that is evidently more consistent with real robot operation and commonly adopted in robotic control), the computational efficiency advantage of the proposed CMPSO-based inverse kinematics algorithm becomes even more significant, consistent with the results shown in Figure 8. Due to the more uniform population initialization, the algorithm uniformly covers the feasible domain in the initial phase, reducing the difficulty of convergence. Additionally, the adaptive mutation strategy greatly improves the success rate of the algorithm.

3.3. Trajectory Planning Experiment

Section 3.1 has verified the feasibility of the algorithm in solving single-point inverse kinematics. On this basis, a trajectory planning test for the mobile manipulator is conducted to further validate the algorithm’s performance in motion control. The specific method is as follows: two points in the manipulator’s workspace 0.5 , 0.7 , 0.5 and ( 0.7 , 0.5 , 0.5 ) , representing a pick-up point and a placement point in the textile workshop, are given. A circular arc in space with a center at ( 0.5 , 0.5 , 0.5 ) and a radius of 0.2 is planned between these two points. A fifth-order polynomial is used for trajectory planning along the circular arc, and 50 interpolation points are obtained based on the interpolation period, as shown in Figure 9.
In this study, the circular end-effector path is discretized into 50 interpolation points. This number of waypoints provides a sufficiently fine spatial resolution for the given radius and workspace scale, so that the discrete points closely approximate a smooth continuous trajectory while keeping the experimental setup and figures concise. It should be noted that the proposed CMPSO-based inverse kinematics solver treats each interpolation point as an independent optimization problem. Therefore, the algorithm can be directly applied to trajectories with a larger number of interpolation points or to longer and more complex paths without any modification of the optimization framework. Combined with the timing results reported in Table 3 and Table 4, where the average computation time per IK query remains well below the 4 ms budget required by a 250 Hz control frequency, this indicates that the proposed method is suitable for real-time trajectory generation even for significantly denser discretizations.
During the trajectory planning process, the PSO algorithm uses the previously computed trajectory point as the starting pose for the current iteration. The first starting pose is the same as that in Equation (21). The pose solutions computed by the algorithm are substituted into Equation (5) to extract and plot the position vectors [ p 1 , p 2 , p 3 ] T . Two-dimensional and three-dimensional comparisons are presented in Figure 10 and Figure 11 (in the three-dimensional view, the trajectory has been translated in the z-direction for visual clarity).
For the 50 trajectory points obtained, the position and orientation errors are calculated based on the definitions in Equations (23) and (24), respectively. The results are illustrated in Figure 12.
Analysis of Figure 8 reveals that the pose error curve obtained by the proposed CMPSO is lower in value and smoother compared to the other three algorithms. The error remains within a limited range [ 1 × 10 5 , 1 × 10 3 ] , indicating a high degree of solution accuracy. These experimental results are consistent with those presented in Section 3.1 and demonstrate that CMPSO has superior precision and stability in solving the inverse kinematics problem.

4. Discussion

In this paper, we addressed the inverse kinematics problem of a mobile manipulator operating in a textile workshop and proposed a CMPSO-based solution capable of achieving high accuracy. By analyzing the coordinate transformation relationships of the mobile manipulator system and adopting the D–H convention, we first established the forward kinematic model of the 9-DOF mobile manipulator. Based on pose error, a “compliance” principle, and joint-limit avoidance, a multi-objective inverse kinematics model was formulated. To overcome the shortcomings of the standard PSO, such as uneven initial population distribution, premature convergence, and a tendency to be trapped in local optima, we introduced three enhancements: Sobol-sequence-based population initialization, logistic-map-based chaotic handling of boundary violations, and a weighted adaptive Gaussian–Cauchy mutation for inferior particles. These components were integrated into a chaotic mutation PSO (CMPSO) algorithm and applied to the multi-objective IK model.
Extensive simulations, including single-point IK solving and trajectory-planning experiments, demonstrated that the proposed CMPSO achieves higher precision and stability compared with the standard PSO and two other enhanced PSO variants (APSO and QPSO). CMPSO consistently yielded the smallest average pose error and variance, indicating superior solution quality and robustness. Moreover, the timing analysis showed that the average computation time per IK query is well below 1 ms, and even the worst-case runtimes satisfy the 4 ms budget required by a 250 Hz control frequency. This implies that the proposed solver is not only suitable for off-line planning, but also has strong potential for real-time control applications, such as online trajectory tracking and whole-body motion generation of mobile manipulators in textile production lines.
Beyond the textile manipulator studied here, the proposed CMPSO framework is largely independent of specific kinematic structures. It requires only the forward kinematics and task-space error definition. As such, it can be extended to other redundant robot systems, including different types of wheeled mobile manipulators and fixed-base manipulators that do not satisfy the Pieper criterion. For these systems, the integrated Sobol initialization, chaotic boundary handling, and adaptive Gaussian–Cauchy mutation are expected to provide similar benefits in terms of maintaining solution-set diversity and improving convergence accuracy in high-dimensional redundant spaces.
From a deployment perspective, several practical considerations will be important for industrial adoption. These include implementing the CMPSO-based IK solver on embedded or industrial controllers with limited computational resources, coping with model uncertainties and sensor noise, and enforcing strict joint, velocity, and workspace constraints to ensure safe operation in cluttered textile factory environments. While the current work focuses on detailed simulations, future research will investigate real-robot validation on a mobile manipulator platform in a textile workshop, integrating the proposed solver with low-level motion controllers and perception modules. This will allow us to evaluate the algorithm under real-world disturbances and hardware limitations and to further refine the method for long-term, reliable deployment in industrial scenarios.

Author Contributions

Conceptualization, Z.W. and W.X.; methodology, Z.W. and W.X.; software, Z.W. and X.X.; validation, Z.W., J.M. and W.X.; formal analysis, Z.W., X.X. and W.X.; investigation, Z.W., J.C. and W.X.; resources, J.M. and J.C.; data curation, Z.W., X.X., J.M. and J.C.; writing—original draft preparation, Z.W.; writing—review and editing, W.X., J.M. and J.C.; project administration, W.X., J.M. and J.C. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the National Key R&D Program of China (No. 2022YFB4700601), the National Key R&D Program of China (No. 2022YFB4700602).

Data Availability Statement

Data is contained within the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Nouinou, H.; Asadollahi-Yazdi, E.; Baret, I.; Nguyen, N.Q.; Terzi, M.; Ouazene, Y.; Yalaoui, F.; Kelly, R. Decision-making in the context of Industry 4.0: Evidence from the textile and clothing industry. J. Clean. Prod. 2023, 391, 136–184. [Google Scholar] [CrossRef]
  2. Pan, R.; Zhang, N.; Xiang, J. Analysis of key technology and application status of textile intelligent factory. J. Cotton Text. Technol. 2023, 51, 105–110. [Google Scholar]
  3. Li, J. Status and Trends of Intelligent Manufacturing in the Cotton Textile Industry. China Text. Lead. 2023, 4, 66–68. [Google Scholar]
  4. Wagaa, N.; Kallel, H.; Mellouli, N. Analytical and deep learning approaches for solving the inverse kinematic problem of a high degrees of freedom robotic arm. Eng. Appl. Artif. Intell. 2023, 123, 106301. [Google Scholar] [CrossRef]
  5. Sandakalum, T.; Ang, M.H. Motion Planning for Mobile Manipulators—A Systematic Review. Machines 2022, 10, 97. [Google Scholar] [CrossRef]
  6. Raja, R.; Dutta, A.; Dasgupta, B. Learning framework for inverse kinematics of a highly redundant mobile manipulator. Robot. Auton. Syst. 2019, 120, 103245. [Google Scholar] [CrossRef]
  7. Khan, A.H.; Li, S.; Chen, D.; Liao, L. Tracking control of redundant mobile manipulator: An RNN based metaheuristic approach. Neurocomputing 2020, 400, 272–284. [Google Scholar] [CrossRef]
  8. Zhao, L.; Zhao, J.; Liu, H. Solving the Inverse Kinematics Problem of Multiple Redundant Manipulators with Collision Avoidance in Dynamic Environments. J. Intell. Robot. Syst. 2021, 101, 30. [Google Scholar] [CrossRef]
  9. Reddy, S.R.; Chembuly, V.V.M.J.S.; Rao, V.V.S.K. Collision-free Inverse Kinematics of Redundant Manipulator for Agricultural Applications through Optimization Techniques. Int. J. Eng. 2022, 35, 1343–1354. [Google Scholar] [CrossRef]
  10. Zhang, X.; Li, G.; Xiao, F.; Jiang, D.; Tao, B.; Kong, J.; Jiang, G.; Liu, Y. An inverse kinematics framework of mobile manipulator based on unique domain constraint. Mech. Mach. Theory 2023, 183, 105273. [Google Scholar] [CrossRef]
  11. Li, X.; Luo, L.; Zhao, H.; Ge, D.; Ding, H. Inverse Kinematics Solution Based on Redundancy Modeling and Desired Behaviors Optimization for Dual Mobile Manipulators. J. Intell. Robot. Syst. 2023, 108, 37. [Google Scholar] [CrossRef]
  12. Jin, T.; Zhu, H.; Zhu, J.; Zhu, S.; He, Z.; Zhang, S.; Song, W.; Gu, J. Whole-Body Inverse Kinematics and Operation-Oriented Motion Planning for Robot Mobile Manipulation. IEEE Trans. Ind. Inform. 2024, 20, 14239–14248. [Google Scholar] [CrossRef]
  13. Xu, J.; Liu, J.; Jing, X.; Zhou, H.; Hu, X.; Ji, J.; Han, Z. Kinematic analysis and optimisation of a gantry spraying robot for ship blocks. Alex. Eng. J. 2025, 116, 385–396. [Google Scholar] [CrossRef]
  14. López-Franco, C.; Hernández-Barragán, J.; Alanis, A.Y.; Arana-Daniel, N.; López-Franco, M. Inverse kinematics of mobile manipulators based on differential evolution. Int. J. Adv. Robot. Syst. 2018, 15, 1729881417752738. [Google Scholar] [CrossRef]
  15. Shi, J.; Mao, Y.; Li, P.; Liu, G.; Liu, P.; Yang, X.; Wang, D. Hybrid Mutation Fruit Fly Optimization Algorithm for Solving the Inverse Kinematics of a Redundant Robot Manipulator. Math. Probl. Eng. 2020, 2020, 6315675. [Google Scholar] [CrossRef]
  16. Liu, X.; Feng, Y.; Yang, Z.; Li, A.; Lu, J. IAFSA for Solving Inverse Kinematics of Redundant Robotic Spraying System. China Mech. Eng. 2022, 33, 1317–1323. [Google Scholar]
  17. Liu, C.; Wang, G.; Jin, Y. Adaptive Particle Swarm Optimization Algorithm for Solving Inverse Kinematics of Mobile Welding Robot. Modul. Mach. Tool Autom. Manuf. Tech. 2023, 58, 50–53. [Google Scholar]
  18. Zhao, G.; Sun, Y.; Jiang, D.; Liu, X.; Tao, B.; Jiang, G.; Kong, J.; Yun, J.; Liu, Y.; Li, G. A 7DOF redundant manipulator inverse kinematic solution algorithm based on bald eagle search optimization algorithm. Soft. Comput. 2024, 28, 13681–13699. [Google Scholar] [CrossRef]
  19. Ram, R.V.; Pathak, P.M.; Junco, S.J. Inverse kinematics of mobile manipulator using bidirectional particle swarm optimization by manipulator decoupling. Mech. Mach. Theory 2019, 131, 385–405. [Google Scholar] [CrossRef]
  20. Jin, M.; Liu, Q.; Wang, B.; Liu, H. An Efficient and Accurate Inverse Kinematics for 7-DOF Redundant Manipulators Based on a Hybrid of Analytical and Numerical Method. IEEE Access 2020, 8, 16316–16330. [Google Scholar] [CrossRef]
  21. Liu, Y.; Xi, J.; Bai, H.; Wang, Z.; Sun, L. A General Robot Inverse Kinematics Solution Method Based on Improved PSO Algorithm. IEEE Access 2021, 9, 32341–32350. [Google Scholar] [CrossRef]
  22. Cao, Y.; Wang, W.; Ma, L.; Wang, X. Inverse Kinematics Solution of Redundant Degree of Freedom Robot Based on Improved Quantum Particle Swarm Optimization. In Proceedings of the 2021 IEEE 7th International Conference on Control Science and Systems Engineering (ICCSSE), Qingdao, China, 30 June–1 August 2021; pp. 68–72. [Google Scholar]
  23. Ning, Y.; Li, T.; Du, W.; Yao, C.; Zhang, Y.; Shao, J. Inverse kinematics and planning/control co-design method of redundant manipulator for precision operation: Design and experiments. Robot. Comput. Integr. Manuf. 2023, 80, 102457. [Google Scholar] [CrossRef]
  24. Eberhart, R.; Kennedy, J. A new optimizer using particle swarm theory. In MHS’95 Proceedings of the Sixth International Symposium on Micro Machine and Human, Nagoya, Japan, 4–6 October 1995; IEEE: New York , NY, USA, 1995; pp. 39–43. [Google Scholar]
  25. Jain, M.; Saihjpal, V.; Singh, N.; Singh, S.B. An Overview of Variants and Advancements of PSO Algorithm. Appl. Sci. 2022, 12, 8392. [Google Scholar] [CrossRef]
  26. Sobol, I.M. On quasi-Monte Carlo integrations. Math. Comput. Simul. 1998, 47, 103–112. [Google Scholar] [CrossRef]
  27. May, R.M. Simple mathematical models with very complicated dynamics. Nature 1976, 261, 459–467. [Google Scholar] [CrossRef] [PubMed]
  28. Dereli, S.; Köker, R. A meta-heuristic proposal for inverse kinematics solution of 7-DOF serial robotic manipulator: Quantum behaved particle swarm algorithm. Artif. Intell. Rev. 2020, 53, 949–964. [Google Scholar] [CrossRef]
Figure 1. Three-dimensional model of the mobile manipulator.
Figure 1. Three-dimensional model of the mobile manipulator.
Symmetry 17 01980 g001
Figure 2. MD–H coordinate description method.
Figure 2. MD–H coordinate description method.
Symmetry 17 01980 g002
Figure 3. Joint coordinate allocation of the Elite manipulator.
Figure 3. Joint coordinate allocation of the Elite manipulator.
Symmetry 17 01980 g003
Figure 4. Comparison between pseudo-random and Sobol sequences.
Figure 4. Comparison between pseudo-random and Sobol sequences.
Symmetry 17 01980 g004
Figure 5. Comparison of performance with different population initialization methods.
Figure 5. Comparison of performance with different population initialization methods.
Symmetry 17 01980 g005
Figure 6. Comparison of performance with different boundary-handling strategies.
Figure 6. Comparison of performance with different boundary-handling strategies.
Symmetry 17 01980 g006
Figure 7. Comparison of performance with different particle mutation strategies.
Figure 7. Comparison of performance with different particle mutation strategies.
Symmetry 17 01980 g007
Figure 8. Convergence curve of fitness values.
Figure 8. Convergence curve of fitness values.
Symmetry 17 01980 g008
Figure 9. Desired Trajectory.
Figure 9. Desired Trajectory.
Symmetry 17 01980 g009
Figure 10. Two-dimensional comparative view.
Figure 10. Two-dimensional comparative view.
Symmetry 17 01980 g010
Figure 11. Three-dimensional comparative view.
Figure 11. Three-dimensional comparative view.
Symmetry 17 01980 g011
Figure 12. Pose Error Compare.
Figure 12. Pose Error Compare.
Symmetry 17 01980 g012
Table 1. D–H table for the Elite manipulator.
Table 1. D–H table for the Elite manipulator.
Link i α i 1 (º) a i 1 (mm) d i (mm) θ i (º)Joint Angle Range (º)
10096 θ 1 ±360
2900138 θ 2 ±360
30418114 θ 3 ±360
4039898 θ 4 ±360
5−90098 θ 5 ±360
690089 θ 6 ±360
Table 2. Statistical performance data of the algorithms.
Table 2. Statistical performance data of the algorithms.
AlgorithmsPSOAPSOQPSOCMPSO
Best Fitness Value 3.364 × 10 3 6.344 × 10 4 9.101 × 10 4 2.478 × 10 4
Worst Fitness Value 5.062 × 10 1 1.694 × 10 2 7.042 × 10 3 8.260 × 10 3
Mean Fitness Value 8.429 × 10 3 6.316 × 10 3 4.291 × 10 3 3.175 × 10 3
Fitness Value Variance 1.469 × 10 2 9.264 × 10 3 4.822 × 10 4 1.773 × 10 4
Average Pose Error 1.332 × 10 2 8.716 × 10 3 6.216 × 10 3 3.975 × 10 3
Table 3. Statistical Results of Solution Time Based on Fixed Iteration Count.
Table 3. Statistical Results of Solution Time Based on Fixed Iteration Count.
AlgorithmsPSOAPSOQPSOCMPSO
Maximum time (ms)2.0152.1591.9001.117
Minimum time (ms)1.6641.3531.1060.874
Average time (ms)1.9321.5021.6310.971
Variance (ms)0.0490.0540.0410.003
Table 4. Statistical Results of Solution Time Based on Convergence Error.
Table 4. Statistical Results of Solution Time Based on Convergence Error.
AlgorithmsPSOAPSOQPSOCMPSO
Maximum time (ms)1.8441.3111.2060.406
Minimum time (ms)1.3050.7550.6340.319
Average time (ms)1.5741.0320.9200.362
Variance (ms)0.0240.0150.0091.42 × 10−3
Success rate52%65%77%96%
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

Xie, W.; Wang, Z.; Ma, J.; Chen, J.; Xie, X. An Inverse Kinematics Solution for Mobile Manipulators in Textile Workshops Based on an Improved Particle Swarm Optimization. Symmetry 2025, 17, 1980. https://doi.org/10.3390/sym17111980

AMA Style

Xie W, Wang Z, Ma J, Chen J, Xie X. An Inverse Kinematics Solution for Mobile Manipulators in Textile Workshops Based on an Improved Particle Swarm Optimization. Symmetry. 2025; 17(11):1980. https://doi.org/10.3390/sym17111980

Chicago/Turabian Style

Xie, Wei, Zhongxu Wang, Jiachen Ma, Jun Chen, and Xingjian Xie. 2025. "An Inverse Kinematics Solution for Mobile Manipulators in Textile Workshops Based on an Improved Particle Swarm Optimization" Symmetry 17, no. 11: 1980. https://doi.org/10.3390/sym17111980

APA Style

Xie, W., Wang, Z., Ma, J., Chen, J., & Xie, X. (2025). An Inverse Kinematics Solution for Mobile Manipulators in Textile Workshops Based on an Improved Particle Swarm Optimization. Symmetry, 17(11), 1980. https://doi.org/10.3390/sym17111980

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