1. Introduction
Vehicles moving in three spatial dimensions, which include aerial, space and underwater vehicles, require attitude control. The vehicles can be modeled as a rigid body with actuators that are used for attitude and translational motion. In this work, we consider control of the attitude motion for maneuverable vehicles without any constraints on the motion. Rigid body attitude is uniquely and globally represented on the Lie group SO(3), which is a compact manifold and not a vector (linear) space. This makes control of rigid body rotational motion on the state space TSO(3), the tangent bundle of SO(3) consisting of all attitudes (orientations) and angular velocities, an inherently nonlinear control problem. Prior research on attitude stabilization and control has shown that global stabilization on TSO(3) with continuous state feedback is not possible [
1,
2,
3].
Instead, the best possible outcome with continuous state feedback is almost global asymptotic stability of desired trajectories or states on TSO(3) [
2,
3,
4]. This best possible outcome is achieved by use of Morse or Morse-Bott functions on SO(3), as part of Lyapunov functions on the state space TSO(3). Consequently, Morse and Morse–Bott functions are necessary to design Lyapunov functions for rigid body control and estimation with guarantees of almost global domains of convergence. Polar Morse functions on SO(3) have a critical set with cardinality four, while Morse-Bott functions on SO(3) have a connected set of critical points; the sets of critical points for both these types of functions are of zero (Lebesgue) measure on SO(3). Their use as part of Lyapunov functions produce feedback systems whose equilibria on TSO(3) correspond to the critical points (attitudes) of the Morse (or Morse–Bott) function on SO(3). The existence of multiple equilibria precludes global asymptotic stability of a single equilibrium state of the continuous state feedback system. By formulating the function appropriately, one can obtain almost global asymptotic stability (AGAS) for the desired attitude state as an equilibrium, while the other equilibria are confined to a set of measure zero in TSO(3).
Designs using constant gain Morse functions have a limitation in certain applications for attitude control that involve large rotations but need fast convergence to a desired attitude. The control approach given in this work is also robust to external disturbance torques due to its rapid convergence and large domain of attraction. In this sense, it is complementary to our previous work on attitude control on SO(3) using integral feedback [
5]. Another use case for the control scheme given here is for attitude synchronization of multi-agent rigid body systems (MARBS), where certain network topologies admit stable but undesirable non-consensus equilibria that correspond to critical points of the Morse or Morse-Bott function that prevent convergence to the consensus configuration for the MARBS network [
6,
7]. Constant gains fix the Hessian of the Morse function at each critical point, and therefore limit our ability to alter stability properties of the crtical point without changing the function’s continuity and resorting to hybrid switching strategies. Recent works on feedback reshaping, multi-agent relative attitude control, and continuous distributed synchronization have demonstrated the need for more flexible approaches to avoid or destabilize undesired equilibria [
8,
9].
In this work, we design and analyze a new class of Morse functions that have continuously time-varying positive gains, for stable and robust attitude control. The principal motivations are two-fold. The time-dependence of gains in the Morse function modifies the local properties (the gradient and Hessian) at each critical point, and this changes the properties of the dynamics near these equilibria, without altering the global stability properties or using discontinuous or hybrid control. The second motivation of practical interest is the use of these functions for attitude synchronization in multi-agent systems. We hypothesize that including time-varying Morse functions for relative attitude measure a network can remove or destabilize undesirable
non consensus and
partial consensus [
7] equilibria arising from certain graph topologies and thus recover almost global synchronization without hybrid switching or global coordination. Preliminary related ideas have appeared in feedback-reshaping and time-varying formation control literature [
10,
11,
12], but a systematic analysis of Morse functions with continuous time-varying gains for single rigid body control and attitude synchronization for MARBS is, to the best of our knowledge, unexplored. This work, which concentrates on developing important fundamental results for single rigid-body attitude control with a continuous time-varying state feedback, can serve as a foundation for future work on attitude synchronization and control of MARBS.
The remainder of this article is organized as follows.
Section 2 defines the problem statement followed by
Section 3 containing analysis and some basic results from prior research using (constant gain) Morse functions. It also introduces time-varying Morse functions, establishes some important results and contrasts it with results obtained using constant Morse functions. This section lays the groundwork for the attitude control approach presented in this article. Next,
Section 4 formulates a time-varying controller using a Morse function with time-varying gains for attitude control. This is followed by
Section 5, which provides numerical simulation results for the designed controller, highlighting the advantages of the proposed time-varying Morse function. Lastly,
Section 6 concludes this article by summarizing contributions and giving planned future directions.
2. Problem Statement
Consider a rigid body with a body-fixed coordinate frame
centered at the center of mass. Let
R be the rotation matrix from
frame to an inertial coordinate frame
. The attitude kinematics and dynamics are described by
where
is the angular velocity of the rigid body in frame
,
is the inertia-like matrix of the rigid body, and
is the external torque acting on that rigid body in frame
. If
denotes a trajectory on SO(3), the tangent vector at
is given by:
where
and
is the Lie algebra of SO(3), represented by
skew-symmetric matrices. This Lie algebra corresponds to the three-dimensional Euclidean vector space
, with the angular velocity vector
being mapped by the
map. This map is a vector space isomorphism from 3D vectors in
to
skew-symmetric matrices in
, and the cross superscript is used as this is equivalent to the cross product operator matrix, i.e.,
for vectors
.
3. Morse Function on SO(3) with Time-Varying Gains
Let
denote the trace inner product defined by:
where
denotes the trace of a matrix. Consider a Morse function defined on the Lie group SO(3) as:
where
is a rotation matrix, and
is a positive diagonal matrix with
. A perturbation (variation) of
R on
is given by:
where
and
is the skew-symmetric cross-product operator matrix associated with
.
3.1. First Variation of the Morse Function
The first variation of
is given by:
Using the commutative property of trace operator and orthogonality of symmetric and skew-symmetric matrices under the trace inner product, eq. (
6) simplifies to:
Now consider
, a time-varying positive diagonal matrix. Then the Morse function becomes:
Next we evaluate the first variation of
U, due to variations in
R. That is, we compute:
where
is a curve on
with
and
, for some
. Thus, the first variation of
U with respect to
R is:
As the Morse function in (
4) varies explicitly with time, its gradient on SO(3) also varies explicitly with time.
3.2. Analysis of Equilibria on SO(3)
Using the identity:
, eq. (
10) simplifies to
where
and
. It can be readily verified by inspection that
where
, are the column vectors of the
identity matrix.
The necessary condition for critical points of the Morse function in eq. (
4) is
, which implies that
, or equivalently
, at the critical points. Therefore, the set of critical points is
Moreover, from eq. (
13),
implies that
. Therefore, set
in eq. (
14) is given by its elements as:
,
, and
denote
(
rad) rotations about the body frame’s first, second and third coordinate axes, respectively. Note that this set of critical points with time-varying
is identical to that obtained with constant
K, which can be readily obtained by setting the right side of eq. (
7) to zero. The second variation of eq. (
4) is obtained by applying the variation operator to eq. (
10), as:
where
denotes the differential of
. Using the trace orthogonality property of symmetric and skew-symmetric matrices, eq. (
16) further simplifies to
Evaluating the second variation of the Morse function given by eq. (
4) on the set
at an instant of time, gives:
Evaluating eq. (
15) at each of the four critical points, we get:
We evaluate the Hessian matrix evaluated for
by taking second partial derivatives of
with respect to
. Denote the Hessian of the Morse function
by:
We define it as:
where
. For
,
and
is the
component of
R. In addition,
, we get the following expression given by,
The Hessian matrices for each
are given by:
Equation (
20) readily reveals that the Hessian of the Morse function evaluated at critical points in the set (
14) depends on time because of
; this is unlike the case with constant
K. This directly affects the indices of these critical values on SO(3), which in turn influences the stability properties of the equilibria on TSO(3) that these critical points correspond to in the feedback system. This is due to the fact that the eigenvalues of
for
are time-varying and may be positive, negative or even momentarily zero depending on the relative values of the
. The only critical point that has a positive definite Hessian and therefore a zero index for all time is the identity
, which corresponds to the desired equilibrium state
. In summary, the time-varying positive diagonal gain matrix
ensures that all critical points of the Morse function that are in the set
, have time-varying indices.
Remark: The index of a critical point of the Morse function is the number of negative eigenvalues of its Hessian,
, for
. If
is constant, then the indices of
and
are 0, 1, 2 and 3, respectively with the minimum attained at
, given that
. However, when
is time-varying, the number of positive and negative eigenvalues of the Hessian at any of the three critical points of the Morse function (i.e., any point in the set
), switch with time depending on
. As the index values can vary with time for
, the dimensions of stable and unstable manifolds associated with these critical points also switch with time. As can be seen from eq. (
20), a switch in the index of one of these three critical points occurs when
for
,
. This results in discrete switching of the index values at these critical points depending on the instantaneous inequality constraint between diagonal elements of
. The index values of the critical points give the dimensions of the stable manifolds of the equilibria of the feedback system corresponding to these critical points. The dimension of the stable manifold
is calculated as
, where 6 is the total dimension of the state-space
. Therefore, the stable manifolds and their dimensions vary over time for these equilibrium points on TSO(3) corresponding to the critical points in
.
4. AGAS Attitude Control Law
The following statement gives a feedback control law on the state space TSO(3) to asymptotically stabilize the desired attitude and angular velocity state .
Theorem 1.
Consider a positive diagonal time-varying such that where are diagonal and , , and is continuous and time-periodic with period T. Consider the attitude control law for the rigid body given by:
where , . This control law makes the state almost globally aymptotically stable (AGAS) and locally exponentially stable.
Proof. The proof is given in two steps. The first step considers the velocity kinematics, where we define a desired angular velocity profile that is guaranteed to steer the attitude R towards the identity attitude I. In the second step, the attitude dynamics is considered, where we formulate the control torque law that forces the true angular velocity of the rigid body to follow the desired angular velocity with finite-time stable (FTS) convergence.
Consider the polar Morse function on SO(3) given by
which depends on the constant part of
as defined in the statement. The time derivative of (
22) is given by
where
and
is the inverse of the cross-product operator map
defined by eq. (
2). A kinematic control law that leads to almost global asymptotically stable (AGAS) convergence of
R to
described by (
1) is given by
where
according to the properties of
. Setting the true angular velocity equal to the desired angular velocity
, and substituting (
24) into the expression (
23) for the time derivative of
, gives:
Simplifying (
25) using (
24) by observing that the vectors
, are mutually orthogonal, leads to:
Eq. (
26) can be rewritten as:
In eq. (
27),
when
. The only (global) minimum of
is at
, while
and
give saddle points with one- and two-dimensional stable manifolds, respectively. The global maximum of
over SO(3) is attained at
. Therefore, with the kinematic control law (
24), all trajectories on SO(3) that do not start on the stable manifolds of
and
, or at
, converge to
. This leads to
being the AGAS equilibrium for this kinematic (velocity level) control system on SO(3).
The next step of this control scheme is to track the desired angular velocity profile given by the kinematic-level control law (
24) so that the true angular velocity converges to this desired profile in a finite time interval. For this, we define the angular velocity tracking error as
. Consider the attitude dynamics of the body given by the second of eqs. (
1), where
is the inertia matrix. Define the following energy-like Lyapunov function of the angular velocity tracking error:
The time derivative of this Lyapunov function along the trajectories of (
1) is given by:
Substituting the finite-time stable
control law (
21) into expression (
29) for
results in,
Therefore, from (
30) and [
13], we conclude that
in finite time, with the settling time upper-bounded as follows:
where
is the initial value of the Lyapunov function in (
28) and
is the initial tracking error in angular velocity. In summary, the control law (
21) ensures FTS convergence of
to
, which in turn ensures AGAS convergence of
to
according to the kinematic control law (
24). □
For numerical simulation studies, this work considers a particular structure of
given by:
where
,
,
is the oscillation frequency and
is an initial phase, for
.
5. Numerical Simulation Results
In this section, a comparative set of numerical simulations with constant gain
K and time-varying gain
of the Morse function is presented. The continuous time dynamics is discretized for numerical simulations in computer. The resulting discrete time dynamics is in the form of a Lie group variational integrator (LGVI) [
14], obtained by applying the discrete Lagrange–d’Alembert principle [
15,
16,
17]. Consider an interval of time
separated into
N equal-length subintervals
for
, with
and
is the time step size. The discrete-time equations are:
For the time-varying gains of the Morse function, we choose the
as described in (
32), with:
For the constant gain Morse function, the gains are selected as
. The simulated time period is 250 seconds. The gain matrix for the dynamic level controller (
21) is
with
. The inertia tensor of the rigid body is
. The initial attitude of the rigid body is
, and the initial angular velocity is
.
Figure 1 shows comparative simulation results for constant
K versus time-varying
. In
Figure 1(a) the principal rotation angle for time-varying
converges to zero (corresponding to identity attitude
), whereas with the constant
K it remains at the initial attitude
.
Figure 1(b) and (c) show the angular velocity and control torque profiles. This numerical simulation demonstrate the usefulness of time-varying gains for the Morse function as an attitude measure, and the role of the resulting time-varying state feedback controller in destabilizing the local stable manifolds of unstable equilibria.
6. Conclusion
This work provides a continous time-varying state dependent feedback attitude controller on TSO(3) based on Morse functions with time-varying gains. As a result, undesirable equilibria for the feedback system of the rigid body are avoided because the indices of these equilibrium points switch discretely in time, and the only always minimum equilibrium on TSO(3) is the identity attitude with zero angular velocity. Simulation results confirm that the time-varying Morse function can prevent system response from “getting stuck" near undesired equilibria of the feedback system and can achieve convergence to the identity attitude. Future work will focus on extending the analysis and results to coordinated relative attitude control of network of unmanned aerial vehicles modeled as multi-agent rigid body systems (MARBS). Distributed gain design for Morse functions for a network of MARBS, integration with observers, and experimental validation on small UAVs, are other future research directions.
Author Contributions
Conceptualization, A.K.S.; methodology, A.K.S. and N.S.; software, N.S.; validation, N.S. and A.K.S.; formal analysis, A.K.S.; investigation, N.S.; resources, A.K.S.; data curation, N.S.; writing—original draft preparation, N.S.; writing—review and editing, A.K.S.; visualization, N.S.; supervision, A.K.S.; project administration, A.K.S.; funding acquisition, A.K.S. All authors have read and agreed to the published version of the manuscript.
Funding
This research was funded by US National Science Foundation (NSF) grant numbers 2132799 and 2343062.
Acknowledgments
The authors acknowledge insights provided by helpful discussions with Prof. Eric Butcher at the University of Arizona.
Conflicts of Interest
The authors declare no conflict of interest.
References
- Bhat, S.; Bernstein, D. A Topological Obstruction to Continuous Global Stabilization of Rotational Motion and the Unwinding Phenomenon. Systems & Control Letters 2000, 39, 63–70. [Google Scholar] [CrossRef]
- Chaturvedi, N.; McClamroch, N. Almost global attitude stabilization of an orbiting satellite including gravity gradient and control saturation effects. In Proceedings of the American Control Conference; 2006. [Google Scholar]
- Chaturvedi, N.; Sanyal, A.; McClamroch, N. Rigid-body attitude control. Control Systems, IEEE 2011, 31, 30–51. [Google Scholar]
- Koditschek, D.E. The application of total energy as a Lyapunov function for mechanical control systems. Contemporary mathematics 1989, 97, 131. [Google Scholar]
- Eslamiat, H.; Wang, N.; Hamrah, R.; Sanyal, A.K. Geometric Integral Attitude Control on SO(3). Electronics 2022, 11. [Google Scholar] [CrossRef]
- Butcher, E.A.; Maadani, M. Rigid Body Attitude Cluster Consensus Control on Weighted Cooperative-Competitive Networks. In Proceedings of the 2024 American Control Conference (ACC). IEEE; 2024; pp. 3049–3054. [Google Scholar]
- Srinivasu, N.; Hashkavaei, N.S.; Sanyal, A.K.; Butcher, E.A. Coordinated Relative Attitude Control and Synchronization of a Multi-body Network of Vehicles. In Proceedings of the 2025 American Control Conference (ACC). IEEE; 2025; pp. 1198–1203. [Google Scholar]
- Casau, P.; Sanfelice, R.G.; Cunha, R.; Silvestre, C. A globally asymptotically stabilizing trajectory tracking controller for fully actuated rigid bodies using landmark-based information. International Journal of Robust and Nonlinear Control 2015, 25, 3617–3640. [Google Scholar] [CrossRef]
- Mathavaraj, S.; Butcher, E.A. Rigid-body attitude control, synchronization, and bipartite consensus using feedback reshaping. Journal of Guidance, Control, and Dynamics 2023, 46, 1095–1111. [Google Scholar] [CrossRef]
- Dong, X.; Yu, B.; Shi, Z.; Zhong, Y. Time-varying formation control for unmanned aerial vehicles: Theories and applications. IEEE Transactions on Control Systems Technology 2014, 23, 340–348. [Google Scholar] [CrossRef]
- Dong, X.; Hu, G. Time-varying formation control for general linear multi-agent systems with switching directed topologies. Automatica 2016, 73, 47–55. [Google Scholar] [CrossRef]
- Maadani, M.; Butcher, E.A. 6-DOF consensus control of multi-agent rigid body systems using rotation matrices. International Journal of Control 2022, 95, 2667–2681. [Google Scholar] [CrossRef]
- Bhat, S.; Bernstein, D. Finite-Time Stability of Continuous Autonomous Systems. SIAM Journal on Control and Optimization 2000, 38, 751–766. [Google Scholar] [CrossRef]
- Nordkvist, N.; Sanyal, A.K. A Lie Group Variational Integrator for Rigid Body Motion in SE(3) with Applications to Underwater Vehicle Dynamics. In Proceedings of the 49th IEEE Conference on Decision and Control (CDC). IEEE; 2010; pp. 5414–5419. [Google Scholar]
- Marsden, J.; West, M. Discrete mechanics and variational integrators. Acta Numerica 2001, 10, 357–514. [Google Scholar] [CrossRef]
- Hairer, E.; Lubich, C.; Wanner, G. Geometric numerical integration, second ed.; Vol. 31, Springer Series in Computational Mathematics, Springer-Verlag, Berlin, 2006; pp. xviii+644. Structure-preserving algorithms for ordinary differential equations.
- Benettin, G.; Giorgilli, A. On the Hamiltonian interpolation of near-to-the identity symplectic mappings with application to symplectic integration algorithms. Journal of Statistical Physics 1994, 74, 1117–1143. [Google Scholar] [CrossRef]
|
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. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (http://creativecommons.org/licenses/by/4.0/).