Next Article in Journal
An Integrated Low-Cost Underwater Navigation Solution for Divers Employing an INS Composed of Low-Cost Sensors Using the Robust Kalman Filter and Sensor Fusion
Previous Article in Journal
mmPhysio: Millimetre-Wave Radar for Precise Hop Assessment
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Identification of Minimum Parameter Set in Robot Dynamics and Excitation Strategy

1
School of Mechatronics Engineering, Henan University of Science and Technology, Luoyang 471003, China
2
Henan Provincial Key Laboratory of Robotics and Intelligent Systems, Luoyang 471003, China
3
School of Materials Science and Engineering, Henan University of Science and Technology, Luoyang 471000, China
*
Author to whom correspondence should be addressed.
Sensors 2025, 25(18), 5749; https://doi.org/10.3390/s25185749
Submission received: 15 July 2025 / Revised: 28 August 2025 / Accepted: 10 September 2025 / Published: 15 September 2025
(This article belongs to the Section Sensors and Robotics)

Abstract

The minimal parameter set is fundamental to robot dynamic identification, enabling efficient and identifiable modeling for control and simulation. In this paper, the Newton–Euler method is employed to formulate the robot dynamics. By leveraging screw theory, the model is expressed in a matrix form that is linear with respect to the robot’s inertial parameters. The Kronecker product is then applied to transform the matrix equation into an equivalent vector–matrix representation. Subsequently, full-rank decomposition is used to reduce the dimensionality of the parameter vector, resulting in the minimal dynamic parameter set of the robot. Following this, excitation signals are sequentially applied to each joint, starting from the end-effector and progressing toward the base, enabling a stepwise identification of the minimal parameter set using the least-squares method. The identified minimal parameters are then incorporated into the mass matrix of the dynamic model, enabling the implementation of forward dynamic simulation. Experimental validation is conducted on a planar 3R robot. The results demonstrate that the sequential excitation strategy accurately identifies dynamic parameters while ensuring the robot’s safety. Furthermore, the forward dynamic simulation closely replicates the kinematic behavior of the actual robot.

1. Introduction

The dynamic model of a robot system plays a crucial role in both simulation and high-precision control [1]. For serial robotic systems, the identification of dynamic parameters fundamentally hinges on determining the minimal parameter set, which encapsulates all identifiable inertial and friction parameters required to predict joint torques [2,3,4]. The need for such a minimal set arises from the intrinsic kinematic and dynamic constraints inherent in the robot’s mechanical structure. These constraints lead to linear dependencies among the inertial parameters in the dynamic equations of motion, resulting in a rank-deficient regressor matrix during the formulation of the identification problem. Moreover, the minimal parameter set cannot be directly applied to forward dynamics, which limits its utility in simulation applications. Recently, reinforcement learning (RL) has shown great potential in robotic control. However, training agents through direct interaction with real robots is time-consuming and potentially unsafe [5,6,7]. By leveraging forward dynamics to simulate the real robot, the entire RL training process can be conducted in a simulated environment, enabling the agent to perform extensive trial-and-error learning. This approach enables the simulation of robot motion and dynamic response under various complex operating conditions, effectively avoiding risks associated with physical interactions, reducing training costs and time, and accelerating model iteration and optimization.
Dynamic models of robotic systems can be formulated using either the Lagrangian or Newton–Euler method, both of which are mathematically equivalent. However, the recursive structure of the Newton–Euler formulation is more suitable for numerical implementation. By employing screw theory, the dynamics of each link can be expressed as a matrix form, thereby transforming the overall dynamic model into a linear matrix equation with respect to the spatial inertia matrices [8,9,10,11]. Fu et al. [10] proposed a method that employs the Kronecker product to convert such linear matrix equations into equivalent vector–matrix forms. By extracting linearly independent columns from the coefficient matrix, the dimensionality of the parameter vector is reduced, yielding the minimal dynamic parameter set. It is worth noting that the Kronecker product and vectorization techniques are applicable to a wide range of linear matrix equations, including but not limited to AXB + CXD = E and AXB = C [12,13,14,15]. The vector–matrix and matrix formulations are mathematically equivalent and yield identical solutions.
In the context of forward dynamics, the mass matrix itself can also be expressed as a linear matrix equation with respect to the spatial inertia matrices. Therefore, the vectorization technique is equally applicable for computing the mass matrix. With the identified minimal parameter set, the mass matrix can be reconstructed and used in conjunction with the inverse dynamics vector–matrix equation to establish a forward dynamic model. In this way, both forward and inverse dynamic models can be derived from the minimal parameter set, thereby extending the applicability of the identified dynamic model beyond torque prediction.
In robotic dynamic parameter identification, excitation signals must be simple, reproducible, and continuously differentiable [16]. Consequently, finite Fourier series have been widely adopted in robotic parameter identification tasks [17,18,19,20]. By minimizing the condition number of the regressor matrix while incorporating constraints on joint positions and velocities, the sensitivity of parameter estimation to measurement noise can be reduced. Tika et al. [19] employed a memetic algorithm to optimize the excitation trajectory, achieving a low condition number and small standard deviations in parameter estimates. Qin et al. [21] used a genetic algorithm to optimize the condition number excitation deriving Fourier series-based excitation trajectories for parameter identification. Nonlinear optimization methods can also be utilized to improve the condition number and generate optimal excitation trajectories. However, the choice of constraints significantly affects the optimization outcome, and these constraints vary across different experimental setups.
In summary, methods that aim to minimize the condition number of the regressor matrix to generate optimal excitation trajectories require numerical optimization, which can be computationally expensive and exhibit variable convergence behavior across trials. Furthermore, the condition number is highly sensitive to joint positions, velocities, and accelerations, and trajectories that minimize it may involve aggressive motions that compromise operational safety. To ensure safety and practical implementation, sinusoidal functions are adopted as excitation trajectories, with only one joint actuated at a time, enabling a single-input multiple-output (SIMO) identification scheme. By sequentially exciting joints from the end-effector toward the base, the complete minimal parameter set is identified in a structured and reliable manner.
The remainder of this paper is organized as follows. Section 2 introduces the foundational materials and methods, including the homogeneous transformation of twists and wrenches based on screw theory, and presents the robot dynamic modeling framework using the Newton–Euler method. Section 3 focuses on the derivation of the minimal dynamic parameter set: it first reformulates the recursive dynamics into a block matrix representation, then applies Kronecker product-based linearization to transform the matrix equation into a vector form, and finally extracts the minimal parameter set via full-rank decomposition. The section concludes with the application of the identified parameters in forward dynamics modeling. Section 4 details the sequential excitation strategy, designed to ensure operational safety and persistent excitation by actuating one joint at a time. Experimental validation and parameter identification results on a planar 3R robot are presented in Section 5, demonstrating the accuracy and effectiveness of the proposed approach. Finally, Section 6 provides concluding remarks and discusses potential extensions to higher-degree-of-freedom robotic systems.

2. Modeling and Methodology

2.1. Homogeneous Transformation of Twists and Wrenches

A velocity twist is a six-dimensional vector composed of angular velocity ω and linear velocity v , defined as V = ω T v T T . As illustrated in Figure 1, the transformation of the velocity twist from link frame i to frame i 1 is given by:
V i 1 = Ad T i 1 , i V i ,
where V i and V i 1 denote the velocity twists expressed in link frames i and i 1 , respectively; Ad T i 1 , i 6 × 6 is the adjoint transformation matrix associated with the homogeneous transformation matrix T i 1 , i , which represents the transformation from frame i to frame i 1 .
For an arbitrary homogeneous transformation matrix T , the adjoint transformation matrix is defined as:
Ad T = R 0 [ t ] R R ,
where R is the rotational part of T , and [ t ] denotes the skew-symmetric matrix corresponding to the translation vector t .
When a link is subjected to a force f and a torque n , the wrench is defined for power computation purposes as F = n T f T T . The transformation of the wrench from frame i to frame i 1 is expressed as:
F i 1 = Ad T i 1 , i 1 T F i ,
where F i and F i 1 are the wrenches expressed in link frames i and i 1 , respectively; Ad T i 1 , i 1 T denotes the transpose of the adjoint transformation matrix corresponding to the inverse transformation T i 1 , i .
The above-defined twists and wrenches are vector representations of elements in the Lie algebra s e ( 3 ) . Twists can also undergo the Lie bracket operation, which can be interpreted as a generalized cross product in the six-dimensional space:
V 2 = ad V 0 V 1 = [ ω 0 ] 0 [ v 0 ] [ ω 0 ] V 1 ,
where V 0 , V 1 , and V 2 are all velocity twists; ad V 0 6 × 6 is the matrix representation of the Lie bracket operator; [ ω 0 ] and [ v 0 ] denote the skew-symmetric matrices corresponding to the angular velocity ω 0 and linear velocity v 0 , respectively.

2.2. Dynamic Modeling of Robots Using the Newton–Euler Method

The Newton–Euler method involves two recursive steps: first, propagating the velocities and accelerations from the robot base to the end-effector; second, computing the forces and torques in reverse from the end-effector back to the base. In both steps, link-fixed coordinate frames must be defined to ensure consistent interpretation of physical quantities.
Most studies [10,11,22,23] begin by explicitly defining the homogeneous transformation between adjacent link frames. However, when using the product-of-exponentials (PoE) formula to formulate the kinematic model, such transformations are not required. Instead, we adopt the same coordinate frame convention used in the PoE-based kinematic modeling, where each link frame is naturally determined by the joint screw axes and the origin vectors defined in the fixed base frame. This approach ensures consistency with the geometric structure of the PoE formulation and avoids the need for additional frame assignments.
As shown in Figure 2, the z-axis of the link-fixed frame, expressed in the fixed frame, is denoted by vector s. To align this axis with the fixed frame’s z-axis, denoted by z = 0 0 1 T , a rotation about the screw axis l = s × z by an angle θ = arccos s z | s | | z | is required. Using Rodrigues’ formula, the rotation matrix that maps the link-fixed frame to the fixed frame is given by:
R = I + [ l ] sin θ + [ l ] [ l ] ( 1 cos θ ) ,
The translational component of the homogeneous transformation is simply the origin vector p. The corresponding homogeneous transformation matrices mapping each link-fixed frame to the fixed frame are denoted as M 0 , i . The homogeneous transformation matrix between adjacent link-fixed frames is then given by:
M i 1 , i = M 0 , i 1 1 M 0 , i .
The homogeneous transformation matrix between adjacent link-fixed frames after robot motion becomes:
T i 1 , i = M i 1 , i e [ ξ i ] θ i ,
where T i 1 , i denotes the homogeneous transformation matrix between adjacent link-fixed frames at an arbitrary time instant; e [ ξ i ] θ i represents the matrix exponential of the Lie algebra element [ ξ i ] θ i , where θ i is the joint rotation angle, and [ ξ i ] is the matrix representation of the screw coordinate [ ξ i ] = [ z ] z 0 0 0 4 × 4 . In the i-th link-fixed frame, the z-axis is axis of rotation, ξ i = z T z 0 T T = [ 0 ,   0 ,   1 ,   0 ,   0 ,   0 ] T .
With the link-fixed coordinate frames defined, the velocity and acceleration screws of each link can be computed recursively.
V i = Ad T i 1 , i 1 V i 1 + θ ˙ i ξ i V ˙ i = Ad T i 1 , i 1 V ˙ i 1 ad θ ˙ i ξ i V i + θ ¨ i ξ i ,
where V i 1 and V i denote the spatial velocity twists of link i 1 and link i , respectively, expressed in their respective link-fixed coordinate frames. The term θ ˙ i ξ i represents the velocity twist generated by the joint i.
The force analysis of each link starts from the end-effector and proceeds backward to the base. The force of link and joint torque are:
F i = G i V ˙ i ad V i T G i V i + Ad T i , i + 1 1 T F i + 1 τ i = F i T ξ i ,
where G i 6 × 6 is the spatial inertia matrix of link i expressed in its own coordinate frame:
G i = I i m i [ r c i ] m i [ r c i ] m i I 3 × 3 ,
Here, I i 3 × 3 is the inertia tensor of link i, m i is its mass, r c i 3 is the vector from the origin to the center of mass in the link-fixed frame, and I 3 × 3 is the 3 × 3 identity matrix.
Since we have defined the link-fixed coordinate frames in advance, the spatial inertia matrix of each link remains constant in its own frame. For link i, there are 10 independent inertial parameters in its own coordinate frame: six related to the inertia tensor— I x x i ,   I y y i ,   I z z i ,   I x y i ,   I y z i ,   I x z i , three related to the center of mass— m i r c x i ,   m i r c y i ,   m i r c z i , and one for the total mass m i . These are collected into a parameter vector λ i 10 × 1 . Using the vectorization operator, the columns of the spatial inertia matrix G i are stacked into a single vector, denoted as vec ( G i ) 36 × 1 . There exists a matrix K 36 × 10 composed solely of 0 s, 1 s, and −1 s such that:
vec ( G i ) = K λ i .

3. Minimal Parameter Set Extraction and Forward Dynamics

3.1. Block Matrix Representation of Recursive Dynamics

For the entire robotic system, the recursive formulations reflect the dynamic coupling between adjacent links. This recursive relationship can be expressed in a block matrix form, which facilitates both computational implementation and further analytical treatment; see details in [8,10].
V = Γ A θ ˙ + W 0 V 0 V ˙ = Γ [ ad θ ˙ ξ ] V + A θ ¨ + W 0 V ˙ 0 ,
where V 0 = [ 0 ,   0 ,   0 ,   0 ,   0 ,   0 ] T is the twist of the robot base. V ˙ 0 6 × 1 denotes the acceleration screw of the robot base. Since the base frame is fixed in the inertial frame and gravity acts along the negative z-axis, we have V ˙ 0 = [ 0 ,   0 ,   0 ,   0 ,   0 ,   9.8 ] T . Detailed symbol representations can be found in Appendix A.
The matrix equation for the overall wrench vector F and joint torques becomes:
F = Γ T [ ad V ] T G V + G V ˙ + W n + 1 F n + 1 τ = A T F ,
where τ = [ τ 1 ,   τ 2 ,   ,   τ n ] T n × 1 .
Substituting Equations (12) and (13) into each other yields the final expression for the joint torque vector:
τ = A T Γ T G Γ A θ ¨ A T Γ T [ ad V ] T G Γ A θ ˙ A T Γ T G Γ [ ad θ ˙ ξ ] Γ A θ ˙ + A T Γ T G Γ W 0 V ˙ 0 + A T Γ T W n + 1 F n + 1 .

3.2. Equivalent Transformation of Linear Matrix Equations and Calculation of the Minimal Inertial Parameter Set

When the robot is not subjected to any external wrench F n + 1 , Equation (14) can be simplified and combined into:
τ = A T Γ T G Γ A θ ¨ Γ ad θ ˙ ξ Γ A θ ˙ + Γ W 0 V ˙ 0 + A T Γ T ad V T G Γ A θ ˙ ,
Let us define the following matrices:
A = A T Γ T n × 6 n , B = Γ A θ ¨ Γ ad θ ˙ ξ Γ A θ ˙ + Γ W 0 V ˙ 0 6 n × 1 , C = A T Γ T ad V T n × 6 n , D = Γ A θ ˙ 6 n × 1 .
The joint torque vector of the entire robotic system is then expressed as:
τ = A G B + C G D .
In numerical analysis, linear matrix equations of the form A X B + C X D = E can be equivalently transformed into a vector–matrix equation using the Kronecker product and the vectorization operator [10,12,13,24]:
B T A + D T C vec ( G ) = τ .
However, in practice, joint friction significantly affects the accuracy of dynamic modeling. Although various friction models have been proposed for robotic systems, the most commonly used are the viscous and Coulomb friction components [22,25]. Therefore, the dynamic model is modified to include these effects:
B T A + D T C vec ( G ) + f v θ ˙ + f c sgn ( θ ˙ ) = τ ,
where f v and f c denote the diagonal matrices of viscous and Coulomb friction coefficients, respectively.
Since G is a block-diagonal matrix, we can simplify the above formulation by following the method outlined in [10]. Partitioning the coefficient matrices accordingly, let A i j 1 × 6 , B j 6 × 1 , C i j 1 × 6 , D j 6 × 1 , and define:
y i j = B j T A i j + D j T C i j 1 × 36 .
Combining this with Equation (19), we obtain:
Y 1 λ 1 + Y 2 λ 2 = Y λ = τ ,
where:
  • Y 1 = y 11 y 12 y 1 n y 21 y 22 y 2 n y n 1 y n 2 y n n K 0 0 0 K 0 0 0 K n × 10 n ,  K from Equation (11).
  • Y 2 = θ ˙ 1 sgn ( θ ˙ 1 ) 0 0 0 0 0 0 θ ˙ 2 sgn ( θ ˙ 2 ) 0 0 0 0 0 0 θ ˙ n sgn ( θ ˙ n ) n × 2 n ,
  • Y = [ Y 1   Y 2 ] ,
  • λ 1 = [ λ 1 T   λ 2 T     λ n T ] T 10 n × 1 ,
  • λ 2 = [ f v 1   f c 1   f v 2   f c 2     f v n   f c n ] T 2 n × 1 ,
  • λ = λ 1 λ 2 .
The coefficient matrix Y depends on the robot’s joint positions, velocities, and accelerations. For different robot configurations, both Y and τ vary. A necessary condition for the vector–matrix equation to admit a unique solution is that Y must be of full column rank. Therefore, at least 12 sets of sampling data are required to potentially achieve full column rank.
It is worth noting that the friction-related submatrix Y 2 is always of full column rank, while Y 1 may contain linearly dependent or zero columns. To address this, a full-rank decomposition is applied to Y 1 .
By collecting m sets of sampling data, the matrix Y 1 is expanded into:
H 1 = Y 1 T 1 Y 1 T 2 Y 1 T m T m n × 10 n .
The full-rank decomposition is performed as follows:
1.
Apply Gaussian elimination to transform H 1 into reduced row echelon form. The column indices corresponding to the pivot elements represent the linearly independent columns of H 1 .
2.
The non-zero rows of the resulting matrix form the right factor of the decomposition, while the corresponding independent column vectors from the original matrix constitute the left factor.
This yields:
H 1 = H 0 K ,
where H 0 m n × r is of full column rank, and K r × 10 n is of full row rank.
Using this decomposition, Equation (21) can be rewritten as:
H 0 H 2 λ 0 λ 2 = H λ m = τ ,
where:
  • H 2 = Y 2 T 1 Y 2 T 2 Y 2 T m T m n × 2 n ,
  • τ = τ T 1 τ T 2 τ T m T m n × 1 ,
  • λ m ( r + 2 n ) × 1 is the minimal parameter set,
  • λ 0 = K λ 1 r × 1 is the reduced-order parameter vector.
All the above transformations are linear. For any sampled H 1 , the full-rank decomposition yields the same full-row-rank matrix K . Hence, the identified minimal parameter set λ m is uniquely determined. To determine whether Equation (24) admits a unique solution, we compute the rank of the augmented matrix [ H   τ ] . If the rank is equal to r + 2 n , a unique solution exists. However, if the rank equals r + 2 n + 1 , it indicates significant measurement noise or error in the sampled joint torques, making parameter estimation unreliable.

3.3. Forward Dynamics

The identified dynamic parameters are only meaningful when they can be consistently applied in both forward and inverse dynamics. While the recursive Newton–Euler formulation inherently provides an inverse dynamic model, forward dynamics require the computation of the mass matrix M ( θ ) . From Equation (14), the mass matrix can be expressed as:
M ( θ ) = A T Γ T GΓA vec ( M ) = ( A A ) vec ( G ) ,
where the linearization technique for matrix equations of the form A X B = C is applied.
To incorporate the minimal inertial parameter set obtained earlier, this expression can be further simplified as:
vec ( M ) = Z K λ 1 = Z 0 λ 0 ,
where:
  • vec ( M ) n 2 × 1 is the vectorized form of the inertia matrix M θ ;
  • K is a block-diagonal extension of the matrix K defined in Equation (11);
  • Z 0 consists of selected columns from Z K corresponding to the same column indices used in the extraction of H 0 .
Partitioning the matrix A into blocks such that each sub-block A i j 1 × 6 , we define the elements of Z as:
Z m j = A i j A z j 1 × 36 , m = n · i + z n ,
where i , j , z { 1 , , n } .
Given the reduced-order parameter vector λ 0 , the vector vec ( M ) can be computed using Equation (26), from which the full inertia matrix M ( θ ) is reconstructed.
With the inertia matrix available, the forward dynamic equation is given by:
θ ¨ = M 1 ( θ ) ( τ Y 0 ( θ , θ ˙ , 0 ) λ 0 Y 2 ( θ ˙ ) λ 2 ) ,
where:
  • Y 0 ( θ , θ ˙ , 0 ) denotes the regressor matrix Y 0 evaluated with zero joint accelerations, but known joint positions and velocities;
  • Y 2 ( θ ˙ ) is the friction-related regressor matrix;
  • λ 0 and λ 2 are the reduced-order inertial and frictional parameter vectors, respectively.
This formulation enables real-time simulation and control of the robot system based on the identified minimal parameter set.

4. Excitation Strategy

The vector–matrix equation given in Equation (24) can be solved using the least squares method, where the estimation error mainly arises from two sources: the excitation trajectory and the measurement noise in the joint torques. The excitation trajectory directly affects the coefficient matrix H , and its condition number determines the sensitivity of the solution to measurement errors [26]. In general, a larger condition number results in a greater estimation error. This relationship can be bounded as:
Δ λ m λ m cond ( H ) Δ τ τ ,
where:
  • cond ( H ) denotes the condition number of the coefficient matrix H ;
  • Δ λ m is the parameter estimation error vector;
  • Δ τ is the joint torque measurement error vector.
Minimizing the condition number of H can therefore serve as an objective function for optimizing the excitation trajectory. Although finite Fourier series can provide flexibility in trajectory design, solving for the optimal trajectory is computationally intensive and may only yield a local optimum.
An alternative approach is to perform single-joint excitation, which results in a sparse structure in the coefficient matrix H . This structure allows further reduction of the parameter vector through full-rank decomposition and facilitates minimization of the condition number. Using sinusoidal functions for single-joint excitation ensures smooth start-up and non-impulsive motion. Moreover, increasing the frequency of the sine wave generally reduces the condition number.
The excitation trajectory for each joint is defined as:
θ i = a i sin ( w i t ) ,
where, θ i is the angular position of joint i ; a i is the amplitude of the sine wave; w i is the angular frequency.
In this work, the following criteria are applied when designing the excitation strategy for dynamic parameter identification:
1.
Sequential Joint Excitation: Start from the distal joints and excite one joint at a time while keeping all other joints fixed at safe positions.
2.
Amplitude determination: The amplitude a i determines the range of motion for each joint and is selected based on the physical constraints of the corresponding joint.
3.
Frequency tuning: To ensure robot safety, the frequency w i is gradually increased until the maximum joint velocity remains within the allowable limits. A relatively high frequency is preferred to reduce the condition number.
During single-joint excitation, although only one joint is actively driven, the passive joints still experience torque variations due to dynamic coupling effects. Therefore, joint torques across all joints must be sampled simultaneously.
Joint position data are typically obtained from motor encoders. Joint velocities and accelerations are estimated through first- and second-order numerical differentiation of the encoder signals. In parameter identification, the actual sampled signals—rather than the planned trajectory values—are used to construct the regressor matrix H . This is because most robotic controllers employ PID (Proportional–Integral–Derivative) control, leading to phase lag and tracking errors between the reference and actual joint positions. Using measured joint states together with sampled torque data helps maintain consistency in the identification process. However, such sampling-induced errors inevitably increase the discrepancy between the identified parameters and their true values.

5. Parameter Identification and Experimental Validation

The experiments were conducted using a custom-designed horizontal lower-limb rehabilitation robot developed in our laboratory. The first three joints of the robot form a planar 3R mechanism, while the fourth joint operates in a plane perpendicular to that of the first three joints. Furthermore, the end-effector has relatively low mass, and the fourth joint exhibits negligible dynamic coupling with the first three joints. Therefore, for the purpose of dynamic modeling and parameter identification, the system can be effectively treated as a planar 3R manipulator.
As shown in Figure 3, the robotic system consists of an industrial personal computer, a controller, servo drivers, servo motors, and the robot body. After designing the excitation trajectories, motion programs are implemented, and feedback data are processed via the upper-level computer. The real-time controller (LinksTech-II) executes the control algorithms and records essential data during operation.
Each axis motor is driven by a Yaskawa single-axis servo driver, which follows pulse commands from the controller. The servo drivers also monitor the motor currents and output estimated motor torque as analog voltage signals via the CN5 interface. The multifunction I/O board PCI6259 in the controller acquires the joint torque data from these analog signals.
The motor encoder provides real-time angular position feedback. In the controller, the actual joint angles are computed based on the known gear transmission ratios. Similarly, the motor torques are converted into joint torques using the same transmission ratios. After completing the robot motion, the recorded joint angle and torque data are exported from the controller for dynamic parameter identification.

5.1. Minimal Parameter Set Identification and Excitation Trajectory Analysis

Establish the link coordinate frames at the joints of the robot used in the experiment, as shown in Figure 4. The origin of the base frame (Frame 0) coincides with that of Link 1, and its z-axis is oriented vertically upward. The x-axis of the base frame points in the direction opposite to the z-axis of Frame 1.
Based on this configuration, the joint axis direction vectors s i and the position vectors of the frame origins p i , both expressed in the base frame, are obtained as listed in Table 1.
Using the formulation derived in Section 2 and Section 3, a symbolic computation program was implemented in MATLAB (2023a) to automatically calculate the coefficient matrix Y in Equation (24). A set of randomly generated joint positions θ , velocities θ ˙ , and accelerations θ ¨ were used as input data to construct the extended regressor matrix H 1 from the original symbolic matrix Y 1 .
The MATLAB function `rref` was employed to compute the reduced row echelon form of H 1 . This operation yielded a full-row-rank matrix K , where the rank was equal to the number of non-zero rows. The column indices corresponding to the pivot columns of the reduced matrix indicate the linearly independent columns of H 1 .
For the robot under study, 12 sets of random input data were used. Through repeated computations, it was observed that regardless of the input data variation, the resulting reduced row echelon forms and the linearly independent column indices remained consistent. This consistency confirms the structural uniqueness of the minimal parameter set for this robotic system.
The matrix formed by selecting these linearly independent columns, denoted Z 0 , was then used to extract the mass matrix M ( θ ) , which plays a central role in forward dynamics modeling.
The amplitude of the excitation trajectory for each joint was determined based on its allowable motion range, as summarized in Table 2. The frequency values were gradually increased during experiments to ensure safety while minimizing the condition number of the regressor matrix H . As expected, increasing the excitation frequency generally led to a reduction in the condition number.
The excitation was applied sequentially starting from the third joint. The resulting condition numbers of H were 47.73, 52.95, and 54.34 for joints 3, 2, and 1, respectively.
Prior to parameter identification, the linearly independent column indices were used to extract the corresponding columns from the symbolic matrix Y 1 , forming a full-column-rank symbolic matrix Y 0 . This matrix, together with the friction-related regressor matrix Y 2 , was saved for use in subsequent identification tasks.
The inertial parameters λ 0 and the joint friction parameters λ 2 were combined into a single minimal parameter vector λ m , which fully characterizes the dynamic behavior of the robot. The identified minimal parameter set is presented in Table 3.
The controller operated at a sampling frequency of 1000 Hz. During each excitation trajectory, partial torque values for each joint were recorded, as shown in Figure 5, Figure 6 and Figure 7. Since the excitation trajectories were periodic, only one cycle of data was used for analysis. Although the encoder readings for joint angles were relatively noise-free, the angular velocities and accelerations—obtained via numerical differentiation—introduced significant noise. To mitigate this, the Zero Phase Filtering method was applied to the velocity and acceleration signals, preserving signal integrity without introducing phase lag.
Filtered joint angle, velocity, and acceleration data were substituted into the precomputed symbolic matrices Y 0 and Y 2 . Using the least-squares method on the regression equation (Equation (24)), the unknown parameter vector λ m was estimated. Given that only one joint was actively excited at a time, the identification results primarily reflected the inertial parameters of the moving joint. Therefore, only the relevant subset of parameters was selected for updating in each trial. The complete minimal parameter set obtained through this process is summarized in Table 3.

5.2. Experimental Validation and Analysis

To validate the accuracy of the identified parameters, Fourier series were utilized to generate smooth, periodic joint trajectories. These trajectories were executed on the physical robot while recording motor current-based torque estimates and simultaneously fed into the inverse dynamics model using the identified minimal parameter set λ m to compute the expected joint torques. Figure 8, Figure 9 and Figure 10 illustrate the comparison between the measured torque values and the estimated torque values derived from the inverse dynamics calculations using the identified parameters.
Key observations:
  • Consistency in trend: The estimated torque values closely follow the trend of the measured torque values, indicating that the identified parameters accurately capture the dynamic characteristics of the robot.
  • Reflection of torque variations: The estimated torques not only match the overall trend but also reflect detailed variations observed in the experimental data, demonstrating the effectiveness of the parameter identification process.
Figure 11 illustrates the error distribution between the estimated and filtered measured joint torques. The root mean square errors (RMSEs) for joints 1, 2, and 3 are 23.76 N·m, 17.09 N·m, and 3.55 N·m, respectively. For joint 1, 50% of the errors fall within −18.73 N·m to 11.17 N·m, with maximum and minimum errors of 50.3 N·m and −86.59 N·m, respectively, and there are 42 outliers. For Joint 2, 50% of the errors fall within −17.72 N·m to 4.83 N·m, with maximum and minimum errors of 36.37 N·m and −45.2 N·m, respectively. For Joint 3, 50% of the errors fall within −1.18 N·m to 3.88 N·m, with maximum and minimum errors of 7.6 N·m and −7.86 N·m, respectively.
The primary sources of error include:
  • Inaccuracies in model identification: Factors such as installation errors and poor lubrication of gearboxes contribute to large friction parameter values.
  • Measurement accuracy: Joint torque measurements, derived from motor current measurements by the actuator, introduce measurement noise and motor friction torque, leading to significant errors at the joint level.
The minimal parameter set was further applied to forward dynamics, and joint accelerations were computed using Equation (28), as shown in Figure 12, Figure 13 and Figure 14. While there were discrepancies between the estimated and measured joint accelerations, their temporal trends are in good agreement. The estimation errors in the minimal parameter set clearly influenced the forward dynamics estimates, the consistency in trends suggests that the minimal parameter set can be effectively used for forward dynamics predictions.

6. Conclusions

Screw theory provides a holistic framework for describing the velocity and force transformations between robotic links, enabling a compact and coordinate-invariant formulation of the Newton–Euler dynamic equations [8]. Moreover, by employing the Kronecker product to transform the linear matrix equation into an equivalent vector–matrix form, the complexity of solving the dynamic model is significantly reduced. This transformation facilitates the identification of inertial parameters in robot dynamics and makes the overall process more computationally efficient [10]. However, only the minimal parameter set, which consists of a unique and identifiable subset of all inertial and friction parameters, can be practically estimated from experimental data. Utilizing this minimal set ensures that the resulting identification is both meaningful and robust for real-world applications.
Main contributions:
1.
Efficient extraction of the unique minimal parameter set via full-rank decomposition. Once the link coordinate frames are defined, the linearized dynamic model yields a regressor matrix Y . Despite being time-varying, this matrix exhibits an invariant set of pivot columns across all motion states. By performing full-rank decomposition on an extended version of the regressor matrix (denoted H ), we consistently obtain the same full row-rank matrix and the same set of linearly independent column indices, regardless of the input trajectory. This property guarantees the uniqueness and repeatability of the minimal parameter set extraction process.
2.
Minimal parameter set application to forward dynamics modeling. The identified minimal parameter set is not only suitable for inverse dynamics estimation but also enables forward dynamics modeling. Specifically, the mass matrix—central to forward dynamics—can be reconstructed using the Kronecker product-based vectorization technique combined with the minimal parameter set. This allows us to derive the forward dynamics model directly from the identified inverse dynamics model, providing a solid foundation for simulation, control design, and real-time prediction of robotic motion behavior.
3.
Sequential joint excitation strategy for safe and accurate identification. In our identification procedure, only one joint is actuated at a time, resulting in a single-input multiple-output (SIMO) identification scheme. This sequential excitation strategy ensures operational safety while allowing for targeted identification of joint-specific inertial parameters. Additionally, by tuning the excitation frequency, the condition number of the regressor matrix can be effectively reduced, thereby improving the numerical stability and accuracy of the least-squares estimation.
The proposed method was validated on a planar 3R serial robot. Experimental results confirm that the sequential joint excitation strategy enables safe and accurate identification of the minimal parameter set, and the reconstructed forward dynamics model closely replicates the actual robot’s dynamic response. Although the current study focuses on a low-degree-of-freedom robot system, the methodology naturally extends to 6-DOF industrial manipulators. The core principles—coordinate frame assignment, symbolic regressor construction, full-rank decomposition, and sequential excitation—remain valid regardless of the robot’s complexity.

Author Contributions

Conceptualization, Z.W. and J.H.; methodology, Z.W. and J.H.; writing—original draft preparation, Z.W.; software, Z.W.; writing—review and editing, J.H., B.G., X.L. and L.L.; project administration, J.H.; funding acquisition, J.H. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Project of Science and Technology of Henan Province, grant number 212102310890 and 212102310249.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data can be accepted on request.

Conflicts of Interest

The authors declare no conflicts of interest.

Appendix A

The recursive velocity equations are given as follows:
Ad T 0 , 1 1 V 0 + V 1 = θ ˙ 1 ξ 1 Ad T 1 , 2 1 V 1 + V 2 = θ ˙ 2 ξ 2 Ad T n 1 , n 1 V n 1 + V n = θ ˙ n ξ n ,
This linear equations can be reformulated into a block matrix form:
I 6 × 6 0 0 Ad T 1 , 2 1 I 6 × 6 0 0 Ad T n 1 , n 1 I 6 × 6 V 1 V 2 V n = ξ 1 0 0 0 ξ 2 0 0 0 ξ n θ ˙ 1 θ ˙ 2 θ ˙ n + Ad T 0 , 1 1 0 0 V 0 .
Define the following composite variables:
V = V 1 T ,   V 2 T ,   ,   V n T T 6 n × 1 ,
θ ˙ = θ ˙ 1 ,   θ ˙ 2 ,   ,   θ ˙ n T n × 1 ,
W 0 = Ad T 0 , 1 1 0 0 6 n × 6 ,
Γ = I 6 × 6 0 0 Ad T 1 , 2 1 I 6 × 6 0 0 Ad T n 1 , n 1 I 6 × 6 1 = I 6 × 6 0 0 Ad T 1 , 2 1 I 6 × 6 0 Ad T 1 , n 1 Ad T n 1 , n 1 I 6 × 6 6 n × 6 n ,
A = ξ 1 0 0 0 ξ 2 0 0 0 ξ n 6 n × n .
Using these definitions, the overall twist vector V of the robot satisfies the following matrix equation:
V = Γ A θ ˙ + W 0 V 0 .
Similarly, based on the recursive formula for acceleration screws, the following block matrix equation can be derived:
I 6 × 6 0 0 Ad T 1 , 2 1 I 6 × 6 0 0 Ad T n 1 , n 1 I 6 × 6 V ˙ 1 V ˙ 2 V ˙ n = ad θ ˙ 1 ξ 1 0 0 0 ad θ ˙ 2 ξ 2 0 0 0 ad θ ˙ n ξ n V 1 V 2 V n + ξ 1 0 0 0 ξ 2 0 0 0 ξ n θ ¨ 1 θ ¨ 2 θ ¨ n + Ad T 0 , 1 1 0 0 V ˙ 0 ,
Define the following composite variables:
V ˙ = V ˙ 1 T ,   V ˙ 2 T ,   ,   V ˙ n T T 6 n × 1 ,
θ ¨ = θ ¨ 1 ,   θ ¨ 2 ,   ,   θ ¨ n T n × 1 ,
[ ad θ ˙ ξ ] = ad θ ˙ 1 ξ 1 0 0 0 ad θ ˙ 2 ξ 2 0 0 0 ad θ ˙ n ξ n 6 n × 6 n .
Then, the overall acceleration screw vector V ˙ satisfies the following matrix equation:
V ˙ = Γ [ ad θ ˙ ξ ] V + A θ ¨ + W 0 V ˙ 0 .
From the recursive wrench propagation formula, we obtain:
I 6 × 6 Ad T 1 , 2 1 T 0 0 I 6 × 6 Ad T n 1 , n 1 T 0 0 I 6 × 6 F 1 F 2 F n = ad V 1 T 0 0 0 ad V 2 T 0 0 0 ad V n T G 1 0 0 0 G 2 0 0 0 G n V 1 V 2 V n + G 1 0 0 0 G 2 0 0 0 G n V ˙ 1 V ˙ 2 V ˙ n + 0 0 Ad T n , n + 1 1 F n + 1 ,
Let:
F = F 1 T ,   F 2 T ,   ,   F n T T 6 n × 1 ,
W n + 1 = 0 0 Ad T n , n + 1 1 6 n × 6 ,
[ ad V ] T = ad V 1 T 0 0 0 ad V 2 T 0 0 0 ad V n T 6 n × 6 n ,
G = G 1 0 0 0 G 2 0 0 0 G n 6 n × 6 n ,
The matrix equation for the overall wrench vector F becomes:
F = Γ T [ ad V ] T G V + G V ˙ + W n + 1 F n + 1 .

References

  1. Nguyen, N.T.; Nguyen, T.N.T.; Tong, H.N.; Truong, H.V.A.; Tran, D.T. Dynamic Parameter Identification Based on the Least Squares Method for a 6-DOF Manipulator. In Proceedings of the 2023 International Conference on System Science and Engineering (ICSSE), Ho Chi Minh, Vietnam, 27–28 July 2023; pp. 301–305. [Google Scholar]
  2. Atkeson, C.G.; An, C.H.; Hollerbach, J.M. Estimation of Inertial Parameters of Manipulator Loads and Links. Int. J. Robot. Res. 1986, 5, 101–119. [Google Scholar] [CrossRef]
  3. Gautier, M.; Khalil, W. Identification of the Minimum Inertial Parameters of Robots. In Proceedings of the 1989 International Conference on Robotics and Automation Proceedings, Scottsdale, AZ, USA, 14–19 May 1989; pp. 1529–1534. [Google Scholar]
  4. Swevers, J.; Verdonck, W.; De Schutter, J. Dynamic Model Identification for Industrial Robots. IEEE Control Syst. Mag. 2007, 27, 58–71. [Google Scholar] [CrossRef]
  5. Qu, M.; Wang, Y.; Pham, D.T. Robotic Disassembly Task Training and Skill Transfer Using Reinforcement Learning. IEEE Trans. Ind. Inform. 2023, 19, 10934–10943. [Google Scholar] [CrossRef]
  6. Xiao, M.; Zhang, T.; Zou, Y.; Chen, S.; Wu, W. Research on Robot Massage Force Control Based on Residual Reinforcement Learning. IEEE Access 2024, 12, 18270–18279. [Google Scholar] [CrossRef]
  7. Orr, J.; Dutta, A. Multi-Agent Deep Reinforcement Learning for Multi-Robot Applications: A Survey. Sensors 2023, 23, 3625. [Google Scholar] [CrossRef] [PubMed]
  8. Lynch, K.M.; Park, F.C. Modern Robotics: Mechanics, Planning, and Control; Cambridge University Press: Cambridge, UK, 2017. [Google Scholar]
  9. Kwon, J.; Choi, K.; Park, F.C. Kinodynamic Model Identification: A Unified Geometric Approach. IEEE Trans. Robot. 2021, 37, 1100–1114. [Google Scholar] [CrossRef]
  10. Fu, Z.T.; Pan, J.N.; Spyrakos-Papastavridis, E.; Lin, Y.-H.; Zhou, X.D.; Chen, X.B.; Dai, J.S. A Lie-Theory-Based Dynamic Parameter Identification Methodology for Serial Manipulators. IEEEASME Trans. Mechatron. 2021, 26, 2688–2699. [Google Scholar] [CrossRef]
  11. Zhang, B.; Tao, T.; Mei, X. A Dynamic Identification Method for General Serial Manipulators from an Analytical Perspective Based on Lie Theory. Nonlinear Dyn. 2024, 112, 19939–19958. [Google Scholar] [CrossRef]
  12. Qiao, Y.P.; Qi, H.S.; Cheng, D.Z. Parameterized Solution to Generalized Sylvester Matrix Equation. In Proceedings of the 2008 27th Chinese Control Conference, Kunming, China, 16–18 July 2008; pp. 2–6. [Google Scholar]
  13. Zhou, B.; Yan, Z.-B.; Duan, G.-R. Unified Parametrization for the Solutions to the Polynomial Diophantine Matrix Equation and the Generalized Sylvester Matrix Equation. In Proceedings of the 2008 Chinese Control and Decision Conference, Yantai, China, 2–4 July 2008; pp. 4075–4080. [Google Scholar]
  14. Ji, Z.; Li, J.f.; Zhou, X.; Duan, F.; Li, T. On Solutions of Matrix Equation AXB = C under Semi-Tensor Product. Linear Multilinear Algebra 2021, 69, 1935–1963. [Google Scholar] [CrossRef]
  15. Liu, Z.; Li, Z.; Ferreira, C.; Zhang, Y. Stationary Splitting Iterative Methods for the Matrix Equation AXB = C. Appl. Math. Comput. 2020, 378, 125195. [Google Scholar] [CrossRef]
  16. Isermann, R.; Münchhof, M. Identification of Dynamic Systems: An Introduction with Applications, 1st ed.; Springer: Berlin/Heidelberg, Germany, 2011. [Google Scholar]
  17. Jiang, S.; Jiang, M.; Cao, Y.; Hua, D.; Wu, H.; Ding, Y.; Chen, B. A Typical Dynamic Parameter Identification Method of 6–Degree–of–Freedom Industrial Robot. Proc. Inst. Mech. Eng. Part I Syst. Control Eng. 2017, 231, 740–752. [Google Scholar] [CrossRef]
  18. Gaz, C.; Cognetti, M.; Oliva, A.; Robuffo Giordano, P.; De Luca, A. Dynamic Identification of the Franka Emika Panda Robot With Retrieval of Feasible Parameters Using Penalty-Based Optimization. IEEE Robot. Autom. Lett. 2019, 4, 4147–4154. [Google Scholar] [CrossRef]
  19. Tika, A.; Ulmen, J.; Bajcinca, N. Dynamic Parameter Estimation Utilizing Optimized Trajectories. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), New York, NY, USA, 24 October 2020–24 January 2021; pp. 7300–7307. [Google Scholar]
  20. Luo, R.; Yuan, J.; Hu, Z.; Du, L.; Bao, S.; Zhou, M. Lie–Theory–Based Dynamic Model Identification of Serial Robots Considering Nonlinear Friction and Optimal Excitation Trajectory. Robotica 2024, 42, 3552–3569. [Google Scholar] [CrossRef]
  21. Qin, Y.; Yin, Z.; Yang, Q.; Zhang, K. Dynamics Parameter Identification of Articulated Robot. Machines 2024, 12, 595. [Google Scholar] [CrossRef]
  22. Liu, G.; Li, Q.; Fang, L.; Han, B.; Zhang, H. A New Joint Friction Model for Parameter Identification and Sensor–Less Hand Guiding in Industrial Robots. Ind. Robot 2020, 47, 847–857. [Google Scholar] [CrossRef]
  23. Gautier, M.; Venture, G. Identification of Standard Dynamic Parameters of Robots with Positive Definite Inertia Matrix. In Proceedings of the 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems, Tokyo, Japan, 3−7 November 2013; pp. 5815–5820. [Google Scholar]
  24. Kittisopaporn, A.; Chansangiam, P.; Lewkeeratiyutkul, W. Convergence Analysis of Gradient-Based Iterative Algorithms for a Class of Rectangular Sylvester Matrix Equations Based on Banach Contraction Principle. Adv. Differ. Equ. 2021, 2021, 17. [Google Scholar] [CrossRef]
  25. Zhou, Y.; Li, Z.; Zhang, X.; Li, Y.; Zhu, M. A Semilinearized Approach for Dynamic Identification of Manipulator Based on Nonlinear Friction Model. IEEE Trans. Instrum. Meas. 2024, 73, 1–20. [Google Scholar] [CrossRef]
  26. Swevers, J.; Ganseman, C.; Tukel, D.B.; de Schutter, J.; Van Brussel, H. Optimal Robot Excitation and Identification. IEEE Trans. Robot. Autom. 1997, 13, 730–740. [Google Scholar] [CrossRef]
Figure 1. Homogeneous transformation of velocity twists and wrenches.
Figure 1. Homogeneous transformation of velocity twists and wrenches.
Sensors 25 05749 g001
Figure 2. Definition of link frames and fixed frame.
Figure 2. Definition of link frames and fixed frame.
Sensors 25 05749 g002
Figure 3. Horizontal lower limb rehabilitation robot system.
Figure 3. Horizontal lower limb rehabilitation robot system.
Sensors 25 05749 g003
Figure 4. Link frame of robot.
Figure 4. Link frame of robot.
Sensors 25 05749 g004
Figure 5. All joint torque values and filtering values when exciting joint 3.
Figure 5. All joint torque values and filtering values when exciting joint 3.
Sensors 25 05749 g005
Figure 6. All joint torque values and filtering values when exciting joint 2.
Figure 6. All joint torque values and filtering values when exciting joint 2.
Sensors 25 05749 g006
Figure 7. All joint torque values and filtering values when exciting joint 1.
Figure 7. All joint torque values and filtering values when exciting joint 1.
Sensors 25 05749 g007
Figure 8. Measurement and estimation of joint 1 torque.
Figure 8. Measurement and estimation of joint 1 torque.
Sensors 25 05749 g008
Figure 9. Measurement and estimation of joint 2 torque.
Figure 9. Measurement and estimation of joint 2 torque.
Sensors 25 05749 g009
Figure 10. Measurement and estimation of joint 3 torque.
Figure 10. Measurement and estimation of joint 3 torque.
Sensors 25 05749 g010
Figure 11. Statistical analysis of the error between the filtered and estimated values of joint torque.
Figure 11. Statistical analysis of the error between the filtered and estimated values of joint torque.
Sensors 25 05749 g011
Figure 12. Estimated and measured angular acceleration of joint 1.
Figure 12. Estimated and measured angular acceleration of joint 1.
Sensors 25 05749 g012
Figure 13. Estimated and measured angular acceleration of joint 2.
Figure 13. Estimated and measured angular acceleration of joint 2.
Sensors 25 05749 g013
Figure 14. Estimated and measured angular acceleration of joint 3.
Figure 14. Estimated and measured angular acceleration of joint 3.
Sensors 25 05749 g014
Table 1. Axis Direction Vectors and Frame Origin Vectors.
Table 1. Axis Direction Vectors and Frame Origin Vectors.
Frame Index Axis   Direction   Vector   s i /m Frame   Origin   Vector   p i /m
1 s 1 = 1 0 0 T p 1 = 0 0 0 T
2 s 2 = 1 0 0 T p 2 = 0.12 0 0.36 T
3 s 3 = 1 0 0 T p 2 = 0.2425 0 0 T
Table 2. Amplitude a i and Frequency w i of Excitation Trajectories.
Table 2. Amplitude a i and Frequency w i of Excitation Trajectories.
Joint Index Amplitude   a i /rad Frequency   w i /rad/s
1 5 π / 9 15
2 2 π / 3 15
3 π / 2 14
Table 3. Identified Minimal Parameter Set λ m .
Table 3. Identified Minimal Parameter Set λ m .
SymbolValue (SI Units)SymbolValue (SI Units)
𝕀 z z 1 + 0.1296 m 2 + 0.1296 m 3 5.888 m 3 r c y 3 0.0016
m 1 r c x 1 + 0.36 m 2 + 0.36 m 3 5.199 f v 1 −157.56
m 1 r c y 1 0.0469 f c 1 −40.402
m 1 r c y 1 3.588 f v 2 −46.302
m 2 r c x 2 0.36 m 3 −1.284 f c 2 −12.837
m 2 r c y 2 0.0381 f v 3 −9.562
𝕀 z z 3 0.111 f c 3 −2.922
m 3 r c x 3 −0.287
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

Wang, Z.; Han, J.; Li, X.; Guo, B.; Lu, L. Research on Identification of Minimum Parameter Set in Robot Dynamics and Excitation Strategy. Sensors 2025, 25, 5749. https://doi.org/10.3390/s25185749

AMA Style

Wang Z, Han J, Li X, Guo B, Lu L. Research on Identification of Minimum Parameter Set in Robot Dynamics and Excitation Strategy. Sensors. 2025; 25(18):5749. https://doi.org/10.3390/s25185749

Chicago/Turabian Style

Wang, Zhiqiang, Jianhai Han, Xiangpan Li, Bingjing Guo, and Lewei Lu. 2025. "Research on Identification of Minimum Parameter Set in Robot Dynamics and Excitation Strategy" Sensors 25, no. 18: 5749. https://doi.org/10.3390/s25185749

APA Style

Wang, Z., Han, J., Li, X., Guo, B., & Lu, L. (2025). Research on Identification of Minimum Parameter Set in Robot Dynamics and Excitation Strategy. Sensors, 25(18), 5749. https://doi.org/10.3390/s25185749

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