Next Article in Journal
Impact of Carpets on Indoor Air Quality
Next Article in Special Issue
ROS-Based Condition Monitoring Architecture Enabling Automatic Faults Detection in Industrial Collaborative Robots
Previous Article in Journal
A Sustainable Polygeneration System for a Residential Building
Previous Article in Special Issue
A Robust H Application for Motor-Link Control Systems of Industrial Manipulators
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Communication

State Observer Based on an Accelerometer for an Elastic Joint with Nonlinear Friction

1
Department of Electrical and Computer Engineering, Sungkyunkwan University, Suwon 16419, Republic of Korea
2
Korean Institute of Industrial Technology, Ansan 15588, Republic of Korea
*
Author to whom correspondence should be addressed.
Submission received: 20 October 2022 / Revised: 14 December 2022 / Accepted: 15 December 2022 / Published: 18 December 2022
(This article belongs to the Special Issue Robots Dynamics: Application and Control)

Abstract

:
This paper presents a state observer for an elastic joint with nonlinear friction via the information from an acceleration sensor. In order to avoid discontinuities, the nonlinear friction of the motor, which includes static, coulomb, and viscous terms, is considered a smooth function. In addition, it uses an acceleration sensor to obtain the information about the link with high uncertainty. The proposed state observer guarantees that the estimation error for the position and velocity of the link connected via an elastic joint containing a nonlinear stiffness (elasticity) converges to zero. In addition, it is shown that the observer gain can be designed by LMI (linear matrix inequality) optimization. Finally, to verify the performance of the proposed observer, the method proposed in this paper is tested by experiments on a two-inertia system with an elastic shaft.

1. Introduction

The design of a robust controller for elastic joint manipulators has attracted much attention over the past several decades. The importance of the control applied to a system is increased when precise and rapid movement needs to be obtained. To obtain high control performance, the precise positioning problem of the elastic joint has been studied for a long time. Several effective control strategies have been devised in [1,2,3,4]. The majority of previously proposed methods need information on the exact state of the joint (position, speed, etc.). However, the research on state estimation is extremely low. In particular, due to the nonlinear characteristics of elastic joints, it is not easy to find the states (e.g., position or velocity of link) of the link side under the constraint that only the states of the motor are known [5,6].
In recent years, there have been several attempts to solve the problem of estimating the position and velocity in mechanical systems [7,8,9]. In particular, the authors in [9] present a robust state observer for elastic joints that contain nonlinear functional components in the stiffness part. The state observer was designed using the results of [10,11,12]. However, this study does not consider the effect of frictional forces. As depicted in Figure 1, elastic joints generally have a nonlinear friction torque that is approximated as affecting the motor side only. The nonlinear characteristics of its friction appear to be especially striking in the low-speed region of the motor [13].
In this brief, we consider the nonlinear frictional force which was not considered in [9]. We present a state observer that overcomes the problem of the state estimation error not being eliminated due to the nonlinear friction. In general, the nonlinear friction model is discontinuous because of the signum function in coulomb friction [14,15]. In order to avoid the discontinuities, the nonlinear friction of the motor, which includes the static, coulomb, and viscous terms, is considered a smooth function. The proposed state observer guarantees that the estimation error for the position and velocity of the link connected via an elastic joint containing a nonlinear stiffness (elasticity) converges to zero. In addition, it is shown that the observer gain can be designed by LMI (linear matrix inequality) optimization. Finally, we conduct experiments on a two-inertia system consisting of two motors.
The rest of this paper is organized as follows: We introduce the problem formulation and provide a design method of the state observer in Section 2. Next, Section 3 shows the stability and performance analysis of the proposed observer. In Section 4, we experimentally test the proposed observer on a servo drive system.

2. Problem Formulation and Solution

We consider an elastic joint model with nonlinear friction and stiffness, as described by [7]:
J l ( θ l ) θ ¨ l + D ( θ ˙ l θ ˙ m ) K ( θ l , θ m ) + C ( θ l , θ ˙ l ) + G ( θ l ) = 0 , J m θ ¨ m + D ( θ ˙ m θ ˙ l ) + K ( θ l , θ m ) + F m ( θ ˙ m ) = τ .
where θ l and θ m are the angular positions of the link-side and motor-side, respectively. J l ( θ l ) and G ( θ l ) , which depend on the position of the link, are the link inertia and the gravity term, respectively. While the coriolis and centrifugal term C ( θ l , ω l ) depend on the position and velocity of the link, the motor inertia J m and the damping D have a constant value. τ is the torque input to the motor. As shown in Figure 1, the nonlinear friction on the motor side F m ( ω m ) is given by:
F m ( ω m ) = f v ω m + f c μ k + ( 1 μ k ) sech ( β ω m ) tanh ( α ω m )
where f v and f c are the kinetic coefficients of viscous and coulomb friction, respectively. α , β and 0 < μ k < 1 are the suitable parameters of the nonlinear friction. Moreover, as shown in [7,9], the stiffness K ( θ l , θ m ) with nonlinear characteristics is expressed by
K ( θ l , θ m ) = k 1 θ B k 2 θ B 3 ( k 1 + 3 k 2 θ B 2 ) ( θ m + θ l θ B ) , if θ m θ l < θ B . k 1 ( θ m θ l ) + k 2 ( θ m θ l ) 3 , if θ m θ l θ B . k 1 θ B + k 2 θ B 3 + ( k 1 + 3 k 2 θ B 2 ) ( θ m θ l θ B ) , if θ m θ l > θ B .
where k 1 , k 2 , and θ B are all position numbers. Here, k 1 and k 2 mean linear and nonlinear stiffness coefficients, respectively. θ B is a break-point, which means the physical limit by the torsion degree between the motor and the link. The representation of (1) can be obtained as follows:
θ ˙ l = ω l , ω ˙ l = J l 1 ( θ l ) D ( ω m ω l ) + K ( θ l , θ m ) C ( θ l , ω l ) G ( θ l ) , θ ˙ m = ω m , ω ˙ m = J m 1 D ( ω l ω m ) K ( θ l , θ m ) F m ( ω m ) + J m 1 τ .
Here, ω l and ω m are the derivatives of θ l and θ m , which represent the angular velocities of the link and motor, respectively.
The final goal of this study is to design a robust state observer that guarantees the asymptotic estimation performance for all the states of the Equation (4). Now, we pose some conditions in order to solve the problem.
Assumption 1. 
The position of motor-side θ m and the acceleration of link-side ω ˙ l are measurable while the link position θ l , the link velocity ω l , and the motor velocity ω m are not.
Assumption 2. 
The motor inertia J m and the damping parameter D and all parameters of the nonlinear friction (2) and stiffness (3) are known.
Now, let
x : = x 1 x 2 x 3 x 4 : = θ l ω l θ m ω m .
Then, the observer design problem considered in this paper can be stated as follows. For the given system (1), find a state observer given in the form
x ^ ˙ ( t ) = f ( t , x ^ , θ m , ω ˙ l , τ )
such that x ^ ( t ) converges to x ( t ) as time goes to infinity.
Inspired by [12], a solution to the problem proposed in the above is given in terms of a state observer for a Lipschitz nonlinear system, which will be described below. First of all, it follows from (4) with (2) and (3) that
x ˙ = A x + Y + Ω ( x ) + B u y 1 = C x
where u : = τ is the input torque and y : = y 1 y 2 T : = θ m ω ˙ l T are the values measurable by Assumption 1, and
A = 0 1 0 0 0 0 0 0 0 0 0 1 J m 1 k 1 J m 1 D J m 1 k 1 J m 1 ( D + f v ) , Y = 0 y 2 0 0 , Ω ( x ) = 0 0 0 J m 1 ( ϕ ( x 1 , x 3 ) + ψ ( x 4 ) ) , B = 0 0 0 J m 1 , C = 0 0 1 0 T , ϕ ( x 1 , x 3 ) = ϕ 1 ( x 1 , x 3 ) = 3 k 2 θ B 2 ( x 3 x 1 ) + 2 k 2 θ B 3 , if x 3 x 1 < θ B , ϕ 2 ( x 1 , x 3 ) = k 2 ( x 3 x 1 ) 3 , if x 3 x 1 θ B , ϕ 3 ( x 1 , x 3 ) = 3 k 2 θ B 2 ( x 3 x 1 ) 2 k 2 θ B 3 , if x 3 x 1 > θ B , ψ ( x 4 ) = f v x 4 + f c μ k + ( 1 μ k ) sech ( β x 4 ) tanh ( α x 4 )
Next, we present a state observer for the system (6) as follows:
x ^ ˙ = A x ^ + Y + Ω ( x ^ ) + B u + L ( y 1 y ^ 1 ) y ^ 1 = C x ^
where the observer gain L is
L = P 1 C 2 ϵ .
Here, the matrix P > 0 is chosen such that for some small ϵ > 0 , the following LMI (linear matrix inequality) [16] holds:
A P + P A + γ 2 I 1 ϵ C C P P I < 0 .
Now, we state the main result of this note, the proof of which is given in the following section, along with a detailed explanation about the proposed observer.
Theorem 1. 
Under Assumptions 1 and 2, the state observer (7) guarantees that the estimation error e ( t ) : = x ( t ) x ^ ( t ) converges to zero as time goes to infinity.

3. Stability and Performance Analysis

In order to prove Theorem 1, we obtain that the nonlinear function Ω ( x ) of (6) has the following property.
Lemma 1. 
Ω ( x ) of (6) is globally Lipschitz. In other words, there exists a positive number γ (the so-called Lipschitz constant) that satisfies the following Lipschitz condition:
Ω ( x ) Ω ( x ^ ) γ x x ^ , x , x ^ R 4 .
In addition, the Lipschitz constant is expressed as:
γ = J m 1 ( 6 k 2 θ B 2 + α f c ) .
Proof. 
The Jacobian matrix of Ω at x is given by:
Ω x = 0 0 0 0 0 0 0 0 0 0 0 0 J m 1 ϕ ( x 1 , x 3 ) x 1 0 J m 1 ϕ ( x 1 , x 3 ) x 3 J m 1 ψ ( x 4 ) x 4
where
ϕ ( x 1 , x 3 ) x 1 = ϕ 1 ( x 1 , x 3 ) x 1 = 3 k 2 θ B 2 , if x 3 x 1 < θ B , ϕ 2 ( x 1 , x 3 ) x 1 = 3 k 2 ( x 3 x 1 ) 2 , if x 3 x 1 θ B , ϕ 3 ( x 1 , x 3 ) x 1 = 3 k 2 θ B 2 , if x 3 x 1 > θ B , ϕ ( x 1 , x 3 ) x 3 = ϕ 1 ( x 1 , x 3 ) x 3 = 3 k 2 θ B 2 , if x 3 x 1 < θ B , ϕ 2 ( x 1 , x 3 ) x 3 = 3 k 2 ( x 3 x 1 ) 2 , if x 3 x 1 θ B , ϕ 3 ( x 1 , x 3 ) x 3 = 3 k 2 θ B 2 , if x 3 x 1 > θ B , ψ ( x 4 ) x 4 = α f c μ k sech 2 ( α x 4 ) + f c ( 1 u k ) β sech ( β x 4 ) tanh ( β x 4 ) tanh ( α x 4 ) + α sech ( β x 4 ) sech 2 ( α x 4 ) α f c μ k + f c ( 1 μ k ) α = α f c .
Thus, the function Ω ( · ) is continuously differentiable on R 4 . In addition, the Ω x is uniformly bounded as follows:
Ω x = J m 1 ϕ ( x 1 , x 3 ) x 1 + ϕ ( x 1 , x 3 ) x 3 + ψ ( x 4 ) x 4 J m 1 6 k 2 θ B 2 + α f c .
Therefore, the proof is complete from ([17] Lemma 3.3). □
Now the dynamics for the estimation error e ( t ) can be expressed as follows:
e ˙ = x ˙ x ^ ˙ = ( A L C ) e + Ω ( x ) Ω ( x ^ ) .
Consider a quadratic Lyapunov function candidate
V ( t ) = e ( t ) P 1 e ( t ) .
Then, it follows from Lemma 1 that the derivative of V ( t ) is given by:
V ˙ = e T ( ( A L C ) P 1 + P 1 ( A L C ) ) e + 2 e T P 1 Ω ( x ) Ω ( x ^ ) e T ( ( A L C ) P 1 + P 1 ( A L C ) ) e + 2 P 1 e Ω ( x ) Ω ( x ^ ) e T ( ( A L C ) P 1 + P 1 ( A L C ) ) e + 2 γ P 1 e e e T ( ( A L C ) P 1 + P 1 ( A L C ) ) e + γ 2 e T P 1 P 1 e + e T e = e T ( ( A L C ) P 1 + P 1 ( A L C ) + γ 2 P 1 P 1 + I ) e .
Next, let P 1 = γ 1 P ; it then follows from the Schur complement that the LMI (9) can be written as:
A P + P A + γ 2 I 1 ϵ C C + P P < 0 ( A L C ) P 1 + P 1 ( A L C ) + γ 2 P 1 P 1 + I < 0
where L = P 1 C 2 ϵ . From Equations (12) and (13), V ˙ < 0 , and the error dynamics (11) are asymptotically stable by ([17] Theorem 4.1), i.e., lim t e ( t ) = 0 .
In actual system, the acceleration y 2 of the vector Y contains measurement noise. On the other hand, the encoder noise for motion position y 1 is small enough to be ignored. For the optimal design for the measurement noise, instead of (6), we consider the noise corrupted system:
x ˙ = A x + Y + Ω ( x ) + B u + Y d d ( t ) y 1 = C x
where d ( t ) R is measurement noise for acceleration and Y d : = 0 1 0 0 T . Now, we consider the minimization of the induced L 2 gain between the acceleration measurement noise d and the estimation error e, i.e., H d e .
Theorem 2. 
For the given system (14) and the proposed observer (7), it is supposed that the noise d ( t ) is bounded. Then, it follows from the observer gain L = P 1 C 2 ϵ that H d e κ if P > 0 , ϵ > 0 , and κ 0 such that
A P + P A + ( 1 + γ 2 ) I 1 ϵ C C P P Y d P I 0 Y d T P 0 κ 2 I < 0 .
The detailed proof is omitted since it is similar to the proof of ([12] Theorem 5). From the above result, it is noted that the observer gain L can be designed by the solution P of the LMI (15) for a given ϵ > 0 and κ 0 .

4. Experiment Results

Even though our goal is to observe all states of the elastic joint expressed as (1), we carry out experiments for a two-inertia system shown in Figure 2 to verify the effectiveness of the proposed observer in the previous section because it represents quite well the dynamic properties of the manipulator having a flexible joint [18]. As shown in Figure 3, a two-motor system consisting of a driving motor and a load motor is illustrated in this experiment. The two motors connected with an elastic shaft and a friction adjustment on the driving motor side are similar to [19]. The proposed observer has been implemented in a high-performance embedded motion controller (manufactured by National Instruments Corporation) with servo motor drivers (manufactured by Panasonic Industry Corporation).
The parameters of the two-inertia system, including the nonlinear stiffness and friction, are listed in Table 1. In addition, the link acceleration ω ˙ l of (6) is obtained from the encoder value of the load motor in Figure 3. In other words, the angle acceleration is obtained by differentiating the position value of the encoder twice. Figure 4 shows the block diagram of the overall system with the proposed state observer. Here, the block Ω ( x ^ ) means the nonlinear terms of the friction and stiffness in the elastic joint model. The difference in design approach between the proposed method and the linear observer is the addition of the block Ω ( x ^ ) and the design method of the observer gain L that depends on the Lipschitz constant γ of Ω ( x ) , as shown in the Equations (7) and (9). The design parameters, including the observer gain L of (8), are chosen as depicted in Table 2.
Now, as shown in Figure 5, we perform an experiment to compare the proposed observer considering the nonlinear stiffness and friction with the conventional observer considering only the nonlinear stiffness of [9]. The actual link trajectory (black solid line) controlled by the pre-installed PID controller is the measured value from the optical incremental encoder on the load motor. From the conventional and proposed observer, the estimated values of the actual link trajectory are indicated by the dash–dot (red color) line and dashed (blue color) line, respectively. For a more detailed performance comparison, we enlarge Figure 5 at 1.2 s and 6.2 s, as depicted in Figure 6. In order to evaluate the estimation performance, we calculate the RMSE (Root Mean Square Error) of the link position estimation error for the conventional method and proposed approach, respectively, as follows.
RMSE ( θ ^ l , θ l ) = 124.8400 for conventional method , 7.8889 for proposed method .
The comparison of the observation performance can also be confirmed from the estimation error of the actual link trajectory, as shown in Figure 7.

5. Conclusions

In this brief, we have proposed a state estimator for an elastic joint with nonlinear friction based on LMI (linear matrix inequality) optimization. From the assumption that the elastic joint has a nonlinear friction model that is considered a smooth function, the proposed estimator has guaranteed that the estimation error of link position and velocity converges to zero. Although the positive definite solution satisfying the LMI cannot be found if the Lipschitz constant is too large, we have applied to a two-inertia system to validate the proposed method, and thus its performance has been verified. Finally, the nonlinear friction model could demonstrate jumping resonance phenomena that can appear in practical nonlinear systems [20]. Thus, further investigation seems to be needed in the future.

Author Contributions

K.-H.L. and H.K. proposed the concept idea, wrote the manuscript, and performed the experiments. T.-Y.K. edited manuscript. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Institute of Information and Communications Technology’s Planning and Evaluation (IITP) grant funded by the Korean government (MSIT) (No. 2022-0-00059, Development of an automated parcel unloading system using a mobile manipulator and AI-based object recognition technology).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Spong, M. Modeling and control of elastic joint robots. J. Dyn. Syst. Meas. Control 1987, 109, 310–319. [Google Scholar] [CrossRef]
  2. Spong, M.; Hutchinson, S.; Vidyasagar, M. Robot Modeling and Control; Wiley: Hoboken, NJ, USA, 2006. [Google Scholar]
  3. Tomei, P. A simple pd controller for robots with elastic joints. IEEE Trans. Autom. Control 1991, 36, 1208–1213. [Google Scholar] [CrossRef]
  4. Bang, J.; Shim, H.; Park, S.; Seo, J. Robust tracking and vibration suppression for a two-inertia system by combining backstepping approach with disturbance observer. IEEE Trans. Ind. Electron. 2010, 11, 618–623. [Google Scholar] [CrossRef]
  5. Jankovic, M. Observer based control for elastic joint robots. IEEE Trans. Robot. Autom. 1995, 11, 618–623. [Google Scholar] [CrossRef]
  6. Lotfi, N.; Namvar, M. Global adaptive estimation of joint velocities in robotic manipulators. IET Control Theory Appl. 2010, 4, 2672–2681. [Google Scholar] [CrossRef]
  7. Moberg, S.; O¨hr, J.; Gunnarsson, S. A benchmark problem for robust control of a multivariable nonlinear flexible manipulator. IFAC World Congress 2008, 41, 1206–1211. [Google Scholar] [CrossRef] [Green Version]
  8. Chen, W.; Tomizuka, M. Comparative study on state estimation in elastic joints. Asian J. Control. 2014, 16, 818–829. [Google Scholar] [CrossRef]
  9. Nam, K.; Lee, S.; Kuc, T.; Kim, H. Position and velocity estimation for two-inertia system with nonlinear stiffness based on acceleration sensor. Sensors 2016, 16, 49. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  10. Rajamani, R. Observers for lipschitz nonlinear systems. IEEE Trans. Automat. Contr. 1998, 43, 397–401. [Google Scholar] [CrossRef]
  11. Rajamani, R.; Cho, Y.M. Existence and design of observers for nonlinear systems: Relation to distance to unobservability. Int. J. Cont. 1998, 69, 717–731. [Google Scholar] [CrossRef]
  12. Song, B.; Hedrick, J.K. Nonlinear observer design for lipschitz nonlinear systems. In Proceedings of the 2011 American Control Conference, San Francisco, CA, USA, 29 June–1 July 2011; pp. 2578–2583. [Google Scholar]
  13. Kim, H.; Sul, S. A new motor speed estimator using kalman filter in low-speed range. IEEE Trans. Ind. Electron. 1996, 43, 498–504. [Google Scholar]
  14. Friedland, B.; Park, Y.J. On adptive friction compensation. IEEE Trans. Autom. Control 1992, 37, 1609–1612. [Google Scholar] [CrossRef]
  15. Tafazoli, S.; de Silva, C.W.; Lawrence, P.D. Tracking control of an electrohydraulic manipulator in the presence of friction. IEEE Trans. Control Syst. Technol. 1998, 6, 401–411. [Google Scholar] [CrossRef] [Green Version]
  16. Boyd, S.; Vandenberghe, L. Convex Optimization; Cambridge University Press: Cambridge, UK, 2004. [Google Scholar]
  17. Khalil, H. Nonlinear Systems; Prentice-Hall: Hoboken, NJ, USA, 2001. [Google Scholar]
  18. Sugiura, K.; Hori, Y. Vibration suppression in 2- and 3-mass system based on the feedback of imperfect derivative of the estimated torsional torque. IEEE Trans. Ind. Electron. 1996, 43, 56–64. [Google Scholar] [CrossRef]
  19. Yun, J.; Su, J.; Kim, Y.; Kim, Y. Robust disturbance observer for two-inertia system. IEEE Trans. Ind. Electron. 2013, 60, 2700–2710. [Google Scholar] [CrossRef]
  20. Buscarino, A.; Famoso, C.; Fortuna, L.; Frasca, M. Multi-jump resonance systems. Int. J. Cont. 2020, 93, 282–292. [Google Scholar] [CrossRef]
Figure 1. Example of nonlinear friction: (a) static + coulomb + viscous friction, (b) static friction, (c) coulomb friction, (d) viscous friction.
Figure 1. Example of nonlinear friction: (a) static + coulomb + viscous friction, (b) static friction, (c) coulomb friction, (d) viscous friction.
Applsci 12 12991 g001
Figure 2. The two-inertia system.
Figure 2. The two-inertia system.
Applsci 12 12991 g002
Figure 3. Experiment Setup.
Figure 3. Experiment Setup.
Applsci 12 12991 g003
Figure 4. Block Diagram of the Overall System.
Figure 4. Block Diagram of the Overall System.
Applsci 12 12991 g004
Figure 5. Observer performance comparison (link position).
Figure 5. Observer performance comparison (link position).
Applsci 12 12991 g005
Figure 6. Enlarged version of Figure 5.
Figure 6. Enlarged version of Figure 5.
Applsci 12 12991 g006
Figure 7. Estimation error of the link position.
Figure 7. Estimation error of the link position.
Applsci 12 12991 g007
Table 1. Parameters of the experimental system.
Table 1. Parameters of the experimental system.
ParameterValueUnit
damping (D)600Nm · s/rad
motor inertia ( J m )0.001027kg · m 2
linear stiffness coefficient ( k 1 )1.5 × 10 6 Nm/rad
nonlinear stiffness coefficient ( k 2 )9.85 × 10 11 Nm/rad 3
breakpoint deflection ( θ B )2arcmin
viscous friction coefficient ( f v )0.006Nm · s/rad
coulomb friction coefficient ( f c )1.5Nm
μ k 0.5
β 0.5
α 5
Table 2. Design parameters for experiments.
Table 2. Design parameters for experiments.
ParameterValue
ϵ 1.0 × 10 6
observer gain L 3.2477 , 3.0286 , 1.6021 , 6.6788 T · 10 2
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Lee, K.-H.; Kim, H.; Kuc, T.-Y. State Observer Based on an Accelerometer for an Elastic Joint with Nonlinear Friction. Appl. Sci. 2022, 12, 12991. https://0-doi-org.brum.beds.ac.uk/10.3390/app122412991

AMA Style

Lee K-H, Kim H, Kuc T-Y. State Observer Based on an Accelerometer for an Elastic Joint with Nonlinear Friction. Applied Sciences. 2022; 12(24):12991. https://0-doi-org.brum.beds.ac.uk/10.3390/app122412991

Chicago/Turabian Style

Lee, Kwang-Hee, Hyungjong Kim, and Tae-Yong Kuc. 2022. "State Observer Based on an Accelerometer for an Elastic Joint with Nonlinear Friction" Applied Sciences 12, no. 24: 12991. https://0-doi-org.brum.beds.ac.uk/10.3390/app122412991

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