Next Article in Journal / Special Issue
Coordination of Multiple Biomimetic Autonomous Underwater Vehicles Using Strategies Based on the Schooling Behaviour of Fish
Previous Article in Journal / Special Issue
Robust Design of Docking Hoop for Recovery of Autonomous Underwater Vehicle with Experimental Results
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Conference Report

Planning the Minimum Time and Optimal Survey Trajectory for Autonomous Underwater Vehicles in Uncertain Current

by
Michael A. Hurni
* and
Kiriakos Kiriakidis
Department of Weapons and Systems Engineering, United States Naval Academy, Annapolis, MD 21402, USA
*
Author to whom correspondence should be addressed.
Robotics 2015, 4(4), 516-528; https://doi.org/10.3390/robotics4040516
Submission received: 10 November 2015 / Revised: 4 December 2015 / Accepted: 11 December 2015 / Published: 16 December 2015
(This article belongs to the Special Issue Underwater Robotics)

Abstract

:
The authors develop an approach to a “best” time path for Autonomous Underwater Vehicles conducting oceanographic measurements under uncertain current flows. The numerical optimization tool DIDO is used to compute hybrid minimum time and optimal survey paths for a sample of currents between ebb and flow. A simulated meta-experiment is performed where the vehicle traverses the resulting paths under different current strengths per run. The fastest elapsed time emerges from a payoff table. A multi-objective function is then used to weigh the time to complete a mission versus measurement inaccuracy due to deviation from the desired survey path.

1. Introduction

The Naval Academy operates a variety of Autonomous Underwater Vehicles (AUVs) for educational and research purposes, including Remote Environmental Measuring Units (REMUS), made by Hydroid [1]. The REMUS AUV is depicted in Figure 1. These AUV units can be programmed to follow a sequence of straight-line path segments between waypoints while collecting data; refer to Figure 1. Using such capability, REMUS can follow any trajectory specified by waypoints from launch to destination; one that has properties in support of its mission such as “minimum time” and “minimum energy.” This paper expands on research done in a previous work, in which the authors investigated the “minimum-time” path in the presence of an unknown current [2]. The case where the magnitude and direction of currents is known has been studied in the optimal control literature and is referred to as Zermelo’s problem [3]. More recently, the same problem has been investigated further in the context of underwater vehicles [4,5,6]. Along the same line of research, solutions in known time-varying current fields have also been reported [7,8]. A real-time approach to path corrections for unknown time-varying currents has been developed in [9]. Using data-based current fields, path planning for realistic ocean variability has been addressed in [10].
Figure 1. (a) REMUS deployed for data collection in the Severn River, Maryland; (b) Linear path specified on the REMUS’ graphical interface.
Figure 1. (a) REMUS deployed for data collection in the Severn River, Maryland; (b) Linear path specified on the REMUS’ graphical interface.
Robotics 04 00516 g001
The objectives of this work are two-fold. First, the authors develop an approach to a “best” time path for Autonomous Underwater Vehicles conducting oceanographic measurements under uncertain current, which is the most significant environmental factor affecting elapsed time or expended energy when following a desired trajectory. Second, a multi-objective function is then used to weigh the time to complete a mission versus measurement inaccuracy due to deviation from the desired path. Ideally, it would seem best to conduct surveys with the smallest possible measurement error. However, there are factors that would require the vehicle to survey an area more quickly at the expense of having some measurement error. For example, an underwater vehicle only has a finite amount of energy to expend in completing its survey. This is not only the energy required to travel the survey path, but also energy to run the onboard sensors and processors. Second, an underwater vehicle can only operate for a finite amount of time before its inertial navigation system develops too much error, causing its survey path to insert even more measurement error. For these reason, it is imperative to be able to accept a certain amount of measurement error in order to reduce the mission time.
In the authors’ view, there are two approaches to tackle the problem of uncertain current. First, knowledge of extreme variations of current can be used for worst-case planning; that is, to select the “best” trajectory from a range of least favorable outcomes. Second, on-board velocity sensors can be used for adaptive planning, where the “best” trajectory from the vehicle’s actual position is recomputed at sample intervals. The authors follow the former approach. To determine the worst-case float plan, the authors solve numerically for the minimum time trajectory, respectively, for a number of known current strengths, S, covering the range between ebb and flow waters.
In addition to the objective “time”, the authors consider “measurement error” due to deviation from the intended geographic location. The reason for deviation is that the AUV need also reach a large number of locations in a short period of time. Typically, oceanographic surveys follow a “lawn-mowing” path conducting measurements at locations along each line segment; refer to Figure 2. In the absence of current, the “minimum-time” paths coincide with the respective line segments. When a current is present, however, the “minimum-time” paths are curved; thus, short travel times come at the expense of measurement error. The problem of energy-exhausting survey missions in fast-flowing waters has been studied in [11]. Trade-offs between energy onboard the AUV and spatial survey error have been investigated in an earlier work [12].
Figure 2. Measurement locations and “minimum-time” path in current.
Figure 2. Measurement locations and “minimum-time” path in current.
Robotics 04 00516 g002
For example, Figure 2 depicts an AUV traversing a “minimum-time” path. The current flows in the unit vector i ^ direction and its profile changes along the unit vector j ^ direction. There are N intended locations for conducting measurement, lying along j ^ , with coordinates ( d , y 1 ) , ... , ( d , y N ) . AUV trajectory is denoted as ( x ( t ) , y ( t ) ) . The (spatially) cumulative error due to deviation from desired measurement locations is:
n = 1 N δ ( y ( t ) y n ) ( x ( t ) d ) 2
where δ ( ) is the Kronecker delta function. In the proposed approach, the authors weigh such “measurement error” against the “time” to traverse the path under current. The multi-objective functional is the weighted sum of two conflicting objectives associated with “time” and (geographic) “measurement error.” Using the numerical optimization tool DIDO [13], the authors analyze the effect that the weighting of these objectives has on their respective fulfillment.
The paper is organized as follows. Under Section 2, the problem is bounded; the scope of the investigation defined. In Section 3, the authors perform an analytical investigation in order to estimate the effect of different current profiles on the optimal trajectories and to weigh the time to complete a mission versus measurement inaccuracy due to deviation from the desired path. Section 4 presents the main results, arrived at by means of the numerical optimization.

2. Modeling Assumptions

Consider an earth-fixed reference frame defined by an orthogonal basis { i ^ , j ^ } ; refer to Figure 3. Relative to the basis, the REMUS’ velocity components have as follows:
x ˙ ( t ) = v cos θ ( t ) + v w , i ( x ( t ) , y ( t ) ) y ˙ ( t ) = v sin θ ( t ) + v w , j ( x ( t ) , y ( t ) )
where v is the vehicle’s speed relative to the water and adjustable in the interval ( 0 , v max ) ; for REMUS, v max = 2.3  m / s . Furthermore, θ denotes the vehicle’s course; v w , i and v w , j are components of water’s flow rate.
Figure 3. Vehicle path in one-dimensional current flow.
Figure 3. Vehicle path in one-dimensional current flow.
Robotics 04 00516 g003
Referring to Figure 2 and Figure 3, the start and end points A and B are at (0, 0) and (0, l); the straight distance l = 1800 m. The current flows along unit vector i only, that is, v w , j ( x , y ) = 0 . Furthermore, the profile of v w , i ( x , y ) is independent of the position x, that is, v w , i ( x , y ) = v w , i ( y ) .
To simplify presentation, the authors adopt the following convention:
x ¯ ˙ ( t ) = f ¯ ( x ¯ ( t ) , u ( t ) ) x ¯ = [ x y ] u = θ
The objective function is:
J = t A t B L ( x ¯ ( t ) , u ( t ) ) d t
For the “minimum time” path from point A to B, the integrand is L ( x ¯ ( t ) , u ( t ) ) = 1 . When the problem weighs both “time” and “accuracy” the integrand becomes L ( x ¯ ( t ) , u ( t ) ) = 1 + r 2 ( x ( t ) d ) 2 . The second objective captures the essence of the cumulative error in Equation (1). If the weight r = 0, the problem becomes one of “minimum time”; if r = , one of “minimum measurement error”.

3. Analytical Approach to an Extremal Path

The following optimization problem results from the given modeling assumptions:
min u J = t A t B L ( x ¯ ( t ) , u ( t ) ) d t
subject to Equation (3).
Let ( x ¯ * , u * ) be an extremum. For the “minimum time” path the Hamiltonian function is:
H ( x ¯ ( t ) , λ ( t ) , u ( t ) ) = L ( x ¯ ( t ) , u ( t ) ) + λ T ( t ) f ( x ¯ ( t ) , u ( t ) ) = 1 + λ T ( t ) f ( x ¯ ( t ) , u ( t ) )
When the problem weighs both “time” and “accuracy” the Hamiltonian function becomes:
H ( x ¯ ( t ) , λ ( t ) , u ( t ) ) = L ( x ¯ ( t ) , u ( t ) ) + λ T ( t ) f ( x ¯ ( t ) , u ( t ) ) = 1 + r 2 ( x ( t ) d ) 2 + λ T ( t ) f ( x ¯ ( t ) , u ( t ) )
where λ T = [ λ 1 λ 2 ] are Lagrange multipliers.
According to Pontryagin’s minimum principle, evaluated at the extremum and at the solution of the adjoint equation:
λ ˙ ( t ) = [ δ H δ x ¯ ] ( x ¯ * , u * )
the Hamiltonian is constant; its value calculated as follows:
H ( x ¯ * ( t ) , λ , u * ( t ) ) = min u H ( x ¯ * ( t ) , λ , u )
At the minimum of the Hamiltonian:
[ δ H δ u ] = 0
Substitution in Equation (6) from Equation (2) results in the following necessary condition for ( x ¯ * , u * ) to be an extremum:
λ 1 ( t ) sin u * ( t ) + λ 2 ( t ) cos u * ( t ) = 0
Equivalently, the decision variable (here, heading input) is optimal, θ*, only if:
tan ( θ * ) = λ 2 λ 1

Adjoint Variables: Effect of Current

From Equations (6) and (12), the current is affecting the heading indirectly and through the adjoint variables. After manipulation, Equation (8) yields the following:
[ λ ˙ 1 λ ˙ 2 ] = [ δ v w , i δ x δ v w , j δ x δ v w , i δ y δ v w , j δ y ] [ λ 1 λ 2 ]
If v w , i ( y ) = v w , a constant flow profile, then the adjoint equations integrate to constants. Equation (12) shows the optimum heading is necessarily constant. The optimum path is a straight line from A to B and the vehicle will have to sail across maintaining the optimum heading in a “crabbing” fashion.
The current profile v w , i ( y ) = v w y l / 2 l , a linear flow profile, is studied in [3]. The adjoint equations are as follows:
[ λ ˙ 1 λ ˙ 2 ] = [ 0 0 v w / l 0 ] [ λ 1 λ 2 ]
Then, the necessary condition for optimum heading becomes:
θ * ( t ) = tan 1 λ 1 v w l ( t t A ) λ 1 t t A
The following piecewise-linear current profile allows for the flow rate to equal zero on the boundaries and to peak in the middle:
v w , i ( y ) = { 2 v w l y .....0 y l 2 2 v w l y + 2 v w ..... l 2 y l
From Equation (13), the second adjoint equation yields:
λ ˙ 2 = { λ 1 2 v w l .....0 y l 2 λ 1 2 v w l ..... l 2 y l
θ * ( t ) = { tan 1 λ 1 2 v w l ( t t A ) λ 1 .....0 y l 2 tan 1 λ 1 2 v w l ( t t A ) λ 1 ..... l 2 y l
The optimum for the “second leg” of the float plan resembles the previous case.
The parabolic flow profile has the same properties as the piecewise-linear and allows for a smooth flow rate:
v w , i ( y ) = 4 v w l 2 y 2 + 4 v w l y
In this case, using Equations (7) and (12), we include both “time” and “accuracy” objectives. The adjoint equations are as follows:
[ λ ˙ 1 λ ˙ 2 ] = [ r ( x l ) 0 ] [ δ v w , i δ x δ v w , j δ x δ v w , i δ y δ v w , j δ y ] [ λ 1 λ 2 ]
For current in the direction of the unit vector i with parabolic profile:
[ λ ˙ 1 λ ˙ 2 ] = [ r ( x l ) 0 ] [ 0 0 4 v w l ( 2 y l + 1 ) 0 ] [ λ 1 λ 2 ]
For the r = 0 “minimum time” case, the adjoint equations become:
[ λ ˙ 1 λ ˙ 2 ] = [ 0 0 4 v w l ( 2 y l + 1 ) 0 ] [ λ 1 λ 2 ]
Since Equations (21) and (22) are, respectively, coupled to Equation (2), the above equations cannot be solved analytically. The authors investigate “minimum time” paths for various parabolic profiles and then weigh “time” versus “accuracy” using the numerical optimization tool DIDO.

4. Numerical Approach to the Optimum Path

DIDO is a MATLAB-based software package that utilizes pseudo-spectral methods to determine an extremal for a properly formulated optimal control problem. Information and illustrations portraying DIDO’s development, viability, and applicability for solving such problems is found in [14,15].

4.1. The Minimum Time Problem

First, DIDO is used to plan a minimum time path between points A at (x, y) = (0, 0) and B at (x, y) = (0, 1828.8) in the presence of a parabolic flow field. The units of distance will be in meters; time in seconds; and angle in radians. The speed is at max (v = 2.3); heading θ = π/2. To cover the range of expected current strength, the authors use S = 5 sets of parabolic flow profiles with maximum current v w = { 0.3 , 0.8 , 1.3 , 1.8 , 2.3 } , respectively. Figure 4 shows the resulting vehicle paths. As the current increases the path length increases as the vehicle must travel further upstream and, then, downstream to complete the maneuver in minimum time. (Notice that the paths resemble sine functions with skewed peaks and troughs).
Second, the authors design a meta-experiment (at present, simulated) programming REMUS to navigate through M = 30 waypoints along each of the S = 5 paths in Figure 4. Every trajectory is traversed S times, each under a different current strength. During the meta-experiment, even though the shape of the flow field is unchanged, the current strength is unknown to REMUS; thus, the vehicle is traversing non-optimal trajectories (unless the actual current happens to match the trajectory’s assumed current). The worst-case float plan emerges from an S × S pay-off table as the one that yields the least elapsed time. The elapsed time, t B t A , along each path and the path average results are contained in Table 1. The “best” time is boldfaced; the associated path is traversed in fastest time irrespective of the current strength.
Figure 4. Minimum time optimal paths for five current flows.
Figure 4. Minimum time optimal paths for five current flows.
Robotics 04 00516 g004
Table 1. Table of elapsed time, t B t A .
Table 1. Table of elapsed time, t B t A .
Current/Path12345
1798804812838920
2821817824849907
3873864858878918
4998987943930955
518711460122510871039
Average t B t A 1072986932916948
In order to investigate “time” vs. “accuracy”, the authors thought it logical to consider the “best” minimum time path as the desired survey path. Deviation from that desired path would result in measurement error. The meta-experiment was expanded to include S = 10 paths. Every path was traversed S times, each under a different current strength. Simulations indicate that the AUV will traverse the “minimum time” path computed for assumed current strength v w 0 = 0.75 v max in the shortest time, on average, given any actual current strength, v w . The authors computed the time to traverse the “minimum time” path above for actual current strength v w v w 0 . Assuming current profile and strength v w 0 , one solves for the “minimum time” path from point A to B using the objective function:
J ( v w , v w 0 ) = t A t B d t
where v w is the actual current strength. To demonstrate the finding, Figure 5 depicts the average travel time, J a v e ( v w 0 ) = 1 10 k = 1 10 J ( v w k , v w 0 ) , on a path planned for assumed current strength v w 0 over k = 1, ..., 10 equally-likely actual current strengths, v w k . The “best” path, corresponding to the lowest average mission time, is the “minimum time” path associated with a current strength of v w 0 = 0.75 v max .
Figure 5. Average time traveled on ten different paths planned for 0 v w 0 v max , where vmax = 2.3 m/s.
Figure 5. Average time traveled on ten different paths planned for 0 v w 0 v max , where vmax = 2.3 m/s.
Robotics 04 00516 g005

4.2. Time vs. Accuracy

The next step is to weigh “time” versus “accuracy” in the generation of the optimal float plan. In this case the integrand of Equation (4) becomes:
L ( x ¯ ( t ) , u ( t ) ) = 1 + r 2 ( x ( t ) d ) 2
The authors examine the two cases where the actual current v w is the same as and different than the assumed current v w 0 = 0.75 v max . The single degree of freedom in the design of the optimum path is the weight r introduced in Equation (24). Performance is assessed in terms of “time” and “measurement error.”
In practice, disparity in sensitivity led the authors to introduce a scaled version of the weight r in Equation (24) as follows:
r 2 = r ʹ max r | x * ( t p ) d |
The quantity max r | x * ( t p ) d | is the worst “measurement error” possible over the range of r. It occurs for r = 0, i.e., “minimum time” path and at tp on either peak of the trajectory. The scaled version, rʹ, is used in the ensuing analysis, but the prime (ʹ) is omitted for brevity.

4.3. Actual Current v w Coincides with Assumed v w 0

Figure 6 depicts ten paths corresponding to a range of weights r (in fact, rʹ). Here, the offset d is set at zero. For small r, the optimum paths are close to “minimum time” trajectories [2]. As expected, large weighting of the second term in Equation (24) results in trajectories that are nearer the desired measurement locations.
Figure 6. Optimum paths for a range of weights r.
Figure 6. Optimum paths for a range of weights r.
Robotics 04 00516 g006
Figure 7 depicts normalized “measurement error” for r [ 0 , 5 ] . Near the knee of the curve, a weight value r = 0.5 results in 80% improvement in accuracy compared to the “minimum time” path.
Figure 7. Measurement error normalized to maximum error for r [ 0 , 5 ] .
Figure 7. Measurement error normalized to maximum error for r [ 0 , 5 ] .
Robotics 04 00516 g007
Similarly, Figure 8 shows the traveled time J ( v w 0 , v w 0 ) from Equation (23) normalized to max r J ( v w 0 , v w 0 ) . The curve has its knee in the same neighborhood of r as the one in Figure 7. Therefore, a weight value r = 0.5 results only in 3% increase in traveled time compared to “minimum time”.
Figure 8. Traveled time normalized to maximum time for r [ 0 , 5 ] .
Figure 8. Traveled time normalized to maximum time for r [ 0 , 5 ] .
Robotics 04 00516 g008

4.4. Actual Current v w Differs from Assumed v w 0

To investigate the case of unknown flow, the authors consider actual current strength v w = v max , i.e., a 25% increase in flow than the previous case. The dashed curve in Figure 9 carries the same information as the one in Figure 7 albeit for a wider range r [ 0 , 20 ] . In comparison, the current curve (solid) is similar in shape with knee in the same vicinity of r.
Figure 9. Normalized measurement error in actual current v max (solid) and 0.75 v max (dashed).
Figure 9. Normalized measurement error in actual current v max (solid) and 0.75 v max (dashed).
Robotics 04 00516 g009
In the companion Figure 10, however, the solid curve has different quality than the dashed curve obtained under known flow and has also been depicted in Figure 8. The knee has shifted to higher values of the weight r and, at the same time, its shape is obtuse due to the change in curvature.
Figure 10. Normalized traveled time in actual current v max (solid) and 0.75 v max (dashed).
Figure 10. Normalized traveled time in actual current v max (solid) and 0.75 v max (dashed).
Robotics 04 00516 g010

5. Conclusions

If REMUS is to sail from A to B under unknown current (strength 1–5 of Table 1) in minimum time, it will achieve the fastest (on average) time by traversing path number four, obtained for the second strongest current (strength 4). Simulations indicate that the AUV will traverse the “minimum time” path computed for assumed current strength v w 0 = 0.75 v max in the shortest time, on average, given any actual current strength, vw.
Based on the evidence at hand, a weight value r = 0.5 results in a good tradeoff between “time” and “accuracy” when the flow is known to be at 0.75vmax, where vmax is the maximum current strength as well as the AUV’s top speed. In the future, the authors will investigated conditions under which a similar tradeoff may be possible in the case of unknown current strength.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. REMUS 100. Available online: http://www.km.kongsberg.com (accessed on 23 March 2014).
  2. Hurni, M.A.; Kiriakidis, K.; Nicholson, J.W. Planning the Minimum Time Course for Autonomous Underwater Vehicle in Uncertain Current. In Proceedings of the ASME Dynamic Systems and Control Conference, Palo Alto, CA, USA, 21–23 October 2013.
  3. Bryson, A.E.; Ho, Y.C. Applied Optimal Control; Hemisphere Publishing Corporation: New York, NY, USA, 1975. [Google Scholar]
  4. Petres, C.; Pailhas, Y.; Patron, P.; Petillot, Y.; Evans, J.; Lane, D. Path planning for autonomous underwater vehicles. IEEE Trans. Robot. 2007, 23, 331–341. [Google Scholar] [CrossRef]
  5. Tinka, A.; Diemer, S.; Madureira, L.; Marques, E.B.; de Sousa, J.B.; Martins, R.; Pinto, J.; da Silva, J.E.; Sousa, A.; Saint-Pierre, P.; et al. Viability-based computation of spatially constrained minimum time trajectories for an autonomous underwater vehicle: Implementation and experiments. In Proceedings of the American Control Conference, St. Louis, MO, USA, 10–12 June 2009; pp. 3603–3610.
  6. Rhoads, B.; Mezic, I.; Poje, A. Minimum time feedback control of autonomous underwater vehicles. In Proceedings of the IEEE Conference on Decision and Control, Atlanta, GA, USA, 15–17 December 2010; pp. 5828–5834.
  7. Techy, L. Optimal navigation in planar time-varying flow: Zermelo’s problem revisited. Intell. Serv. Robot. 2011, 4, 271–283. [Google Scholar] [CrossRef]
  8. Lolla, T.; Ueckermann, M.P.; Yigit, K.; Haley, P.J., Jr.; Lermusiaux, P.F.J. Path planning in time dependent flow fields using level set methods. In Proceedings of the IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, 14–18 May 2012; pp. 3603–3610.
  9. Jordan, M.A.; Bustamante, J.L. A Real-Time Approach to Optimal Energy-Consumption for Autonomous Underwater Vehicles in Unknown Time-Varying Flow Fields. In Proceedings of the 5th International Conference on Physics and Control, Leon, Spain, 5–8 September 2011.
  10. Garau, B.; Bonet, M.; Alvarez, A.; Ruiz, S.; Pascual, A. Path Planning for Autonomous Underwater Vehicles in Realistic Oceanic Current Fields: Application to Gliders in the Western Mediterranean Sea. J. Marit. Res. 2009, 6, 5–22. [Google Scholar]
  11. Kruger, D.; Stolkin, R.; Blum, A.; Briganti, J. Optimal AUV path planning for extended missions in complex, fast-flowing estuarine environments. In Proceedings of the IEEE International Conference on Robotics and Automation, Roma, Italy, 10–14 April 2007.
  12. Bellingham, J.; Willcox, J. Optimizing AUV oceanographic surveys. In Proceedings of the IEEE Symposium of AUVT, Monterey, CA, USA, 2–6 June 1996.
  13. Ross, I.M. A Beginner’s Guide to DIDO: A MATLAB Application Package for Solving Optimal Control Problems; Elissar: Carmel, IN, USA, 2007. [Google Scholar]
  14. Ross, I.M.; Fahroo, F. Issues in the real-time computation of optimal control. J. Math. Model. 2006, 43, 1172–1188. [Google Scholar] [CrossRef]
  15. IRoss, M.; D’Souza, C.; Fahroo, F.; Ross, J. A fast approach to multi-stage launch vehicle trajectory optimization. In Proceedings of the AIAA Guidance, Navigation, and Control Conference and Exhibit, Toronto, ON, Canada, 2–5 August 2010.

Share and Cite

MDPI and ACS Style

Hurni, M.A.; Kiriakidis, K. Planning the Minimum Time and Optimal Survey Trajectory for Autonomous Underwater Vehicles in Uncertain Current. Robotics 2015, 4, 516-528. https://doi.org/10.3390/robotics4040516

AMA Style

Hurni MA, Kiriakidis K. Planning the Minimum Time and Optimal Survey Trajectory for Autonomous Underwater Vehicles in Uncertain Current. Robotics. 2015; 4(4):516-528. https://doi.org/10.3390/robotics4040516

Chicago/Turabian Style

Hurni, Michael A., and Kiriakos Kiriakidis. 2015. "Planning the Minimum Time and Optimal Survey Trajectory for Autonomous Underwater Vehicles in Uncertain Current" Robotics 4, no. 4: 516-528. https://doi.org/10.3390/robotics4040516

Article Metrics

Back to TopTop