Next Article in Journal
Enhancement of ADAS with Driver-Specific Gaze Profiling Algorithm—Pilot Case Study
Previous Article in Journal
High-Performance One-Quadrant DC Drive for Pumping Applications Using Ultra-Sparse Matrix Rectifier
Previous Article in Special Issue
Modeling and Control of Distributed-Propulsion eVTOL UAV Hovering Flight
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Time-Varying Feedback for Rigid Body Attitude Control

Mechanical & Aerospace Engineering, Syracuse University, Syracuse, NY 13244, USA
*
Author to whom correspondence should be addressed.
Vehicles 2025, 7(4), 143; https://doi.org/10.3390/vehicles7040143
Submission received: 27 October 2025 / Revised: 24 November 2025 / Accepted: 24 November 2025 / Published: 28 November 2025
(This article belongs to the Special Issue Air Vehicle Operations: Opportunities, Challenges and Future Trends)

Abstract

Stable attitude control of unmanned or autonomous operations of vehicles moving in three spatial dimensions is essential for safe and reliable operations. Rigid body attitude control is inherently a nonlinear control problem, as the Lie group of rigid body rotations is a compact manifold and not a linear (vector) space. Prior research has shown that the largest possible domain of convergence is provided by smooth attitude feedback control laws are obtained using a Morse function on SO ( 3 ) as a measure of the attitude stabilization or tracking error. A polar Morse function on SO ( 3 ) has four critical points, which precludes the possibility of global convergence of the attitude state. When used as part of a Lyapunov function on the state space (the tangent bundle TSO ( 3 ) ) of attitude and angular velocity, it gives a globally continuous state-dependent feedback control scheme with the minimum of the Morse function as the almost globally asymptotically stable (AGAS) attitude state. In this work, we explore the use of explicitly time-varying gains for Morse functions for rigid body attitude control. This strategy leads to discrete switching of the indices of the three non-minimum critical points that correspond to the unstable equilibria of the feedback system. The resulting time-varying feedback controller is proved to be AGAS, with the additional desirable property that the time-varying gains destabilize the (locally) stable manifolds of these unstable equilibria. Numerical simulations of the feedback system with appropriate time-varying gains show that a trajectory starting from an initial state close to the stable manifold of an unstable equilibrium, converges to the desired stable equilibrium faster than the corresponding feedback system with constant gains.

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 applications 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 critical point without changing the function’s continuity and resorting to hybrid switching strategies. A backstepping-based approach for rigid body control using Morse-Lyapunov functions appeared in [8]. Recent work on feedback reshaping [6,9,10], decentralized consensus protocol [11] for relative attitude control, and hybrid strategies for trajectory tracking control [12] have demonstrated the need for more flexible approaches to avoid or destabilize undesired equilibria.
In this work, we design and analyze a new class of polar 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) of the non-minimum critical points, and this changes the properties of the dynamics near the equilibria corresponding to these critical points, 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 using time-varying Morse functions for relative attitude measure in a network of rigid bodies can destabilize or remove undesirable non-consensus and partial consensus [7] equilibria arising from certain graph topologies, and thus recover almost global synchronization without hybrid switching or discontinuous control. Preliminary related ideas have appeared in feedback-reshaping and time-varying formation control literature [13,14,15], but a systematic analysis of Morse functions with continuous time-varying gains for single rigid body control 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 B centered at the center of mass. Let R be the rotation matrix from B frame to an inertial coordinate frame I . The attitude kinematics and dynamics are described by:
R ˙ = R Ω × , J Ω ˙ = Ω × J Ω + τ ,
where Ω is the angular velocity of the rigid body in frame B , J R 3 × 3 is the inertia-like matrix of the rigid body, and τ R 3 is the control torque acting on that rigid body in frame B . If R ( t ) denotes a trajectory on SO ( 3 ) , the tangent vector at R ( t ) is given by:
R ˙ = R Ω × , where   Ω × = 0 Ω 3 Ω 2 Ω 3 0 Ω 1 Ω 2 Ω 1 0 so ( 3 ) ,
where Ω ( t ) × so ( 3 ) and so ( 3 ) is the Lie algebra of SO ( 3 ) , represented by 3 × 3 skew-symmetric matrices. This Lie algebra corresponds to the three-dimensional Euclidean vector space R 3 , with the angular velocity vector Ω = [ Ω 1 Ω 2 Ω 3 ] T R 3 being mapped by the ( · ) × : R 3 so ( 3 ) map. This map is a vector space isomorphism from 3D vectors in R 3 to 3 × 3 skew-symmetric matrices in so ( 3 ) , and the cross superscript is used as this is equivalent to the cross product operator matrix, i.e., a × b = a × b for vectors a , b R 3 . The attitude dynamics (2) generates trajectories in the state space ( R ( t ) , Ω ( t ) ) SO ( 3 ) × so ( 3 ) TSO ( 3 ) . Consider attitude control of the rigid body with a control law designed for τ to stabilize the attitude trajectory to ( I , 0 ) SO ( 3 ) × so ( 3 ) .

3. Morse Function on SO(3) with Time-Varying Gains

Let · , · : R 3 × 3 R denote the trace inner product defined by:
A , B = tr ( A T B ) ,
where tr ( · ) denotes the trace of a matrix. Consider a polar Morse function defined on the Lie group SO ( 3 ) as:
U 0 ( R ) = K , I 3 R = tr ( K ( I 3 R ) ) ,
where R SO ( 3 ) is a rotation matrix, and K R 3 × 3 is a constant positive diagonal matrix with k 1 > k 2 > k 3 > 0 . A variation of R on SO ( 3 ) is given by:
δ R = R Σ × , Σ × so ( 3 ) ,
where Σ R 3 and Σ × so ( 3 ) is the skew-symmetric cross-product operator matrix associated with Σ .

3.1. First Variation of the Morse Function

The first variation of U 0 ( R ) is given by:
δ U 0 ( R , Σ ) = δ K , I 3 R = K , δ R = K , R Σ × .
Using the commutative property of trace operator and orthogonality of symmetric and skew-symmetric matrices under the trace inner product, Equation (6) simplifies to:
δ U 0 ( R , Σ ) = 1 2 K R R T K , Σ × = S K ( R ) T Σ , where S K ( R ) = vex ( K R R T K ) ,
and vex ( χ × ) = χ = [ χ 1 , χ 2 , χ 3 ] T R 3 is the inverse of the cross-product operator map ( · ) × . The following result is used in our main result in the next section, and its detailed proof is given in [16]. For brevity, we omit the proof in this paper.
Lemma 1.
Let K be as defined in Equation (10) and S K ( R ) be as given in the Equation (7). Let N SO ( 3 ) be a closed subset containing the identity in its interior, defined by
N = R SO ( 3 ) : R i i 0   a n d   R i j R j i 0 i , j { 1 , 2 , 3 } , i j .
If R N , then it satisfies
S K ( R ) T S K ( R ) U 0 ( R ) = tr ( K K R ) .
Now consider K = K ( t ) , a time-varying positive diagonal matrix. Then the Morse function becomes:
U ( R , t ) = K ( t ) , I 3 R .
Next we evaluate the first variation of U, due to variations in R. That is, we compute:
δ U ( R , Σ , t ) = d d ϵ ϵ = 0 U ( R ( ϵ ) , t ) ,
where R ( ϵ ) is a curve on SO ( 3 ) with R ( 0 ) = R and d d ϵ ϵ = 0 R ( ϵ ) = R Σ × , for some Σ × so ( 3 ) . Thus, the first variation of U with respect to R is:
δ U ( R , Σ , t ) = K ( t ) , R Σ ×
= 1 2 K ( t ) R R T K ( t ) , Σ × .
As the Morse function in (10) 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: tr ( a × b × ) = 2 a T b , Equation (12) simplifies to
δ U = S K ( t ) ( R ) T Σ ,
where S K ( t ) ( R ) = vex ( K ( t ) R R T K ( t ) ) and vex : so ( 3 ) R 3 is as defined by Equation (7). It can be readily verified by inspection that
S K ( t ) ( R ) = l = 1 3 k l ( t ) ( R T e l ) × e l ,
where e l , l = 1 , 2 , 3 , are the column vectors of the 3 × 3 identity matrix.
The necessary condition for critical points of the Morse function in Equation (10) is δ U ( R , t ) = 0 , which implies that S K ( t ) ( R ) = 0 , or equivalently K ( t ) R = R T K ( t ) , at the critical points. Therefore, the set of critical points is
S c : = R SO ( 3 ) S K ( t ) ( R ) = 0 .
Moreover, from Equation (15), S K ( t ) ( R ) = 0 implies that R T e l = ± e l e l = ± R e l . Therefore, set S c in Equation (16) is given by its elements as:
S c = { I = [ e 1 , e 2 , e 3 ] , E 1 = [ e 1 , e 2 , e 3 ] , E 2 = [ e 1 , e 2 , e 3 ] , E 3 = [ e 1 , e 2 , e 3 ] } SO ( 3 ) .
E 2 , E 3 , and E 4 denote 180 ( π rad) rotations about the body frame’s first, second and third coordinate axes, respectively. Note that this set of critical points with time-varying K ( t ) is identical to that obtained with constant K, which can be readily obtained by setting the right side of Equation (7) to zero. The second variation of Equation (10) is obtained by applying the variation operator to Equation (12), as:
δ 2 U ( R , Σ , δ Σ , t ) = K ( t ) , R ( Σ × ) 2 R δ Σ × ,
where δ Σ denotes the differential of Σ R 3 . Using the trace orthogonality property of symmetric and skew-symmetric matrices, Equation (18) further simplifies to
δ 2 U = 1 2 K ( t ) R R T K ( t ) , δ Σ × R T K ( t ) + K ( t ) R , ( Σ × ) 2 .
The following result gives the Hessian matrices for each element in the set of critical points S c SO ( 3 ) of U ( R , t ) .
Proposition 1.
The Hessian matrices for the critical points R S c of the Morse-function with time-varying gains U ( R , t ) , are given by:
H U ( I , t ) = 2 diag [ k 2 ( t ) + k 3 ( t ) , k 3 ( t ) + k 1 ( t ) , k 1 ( t ) + k 2 ( t ) ] , H U ( E 1 , t ) = 2 diag [ ( k 2 ( t ) + k 3 ( t ) ) , k 1 ( t ) k 3 ( t ) , k 1 ( t ) k 2 ( t ) ] , H U ( E 2 , t ) = 2 diag [ k 2 ( t ) k 3 ( t ) , ( k 3 ( t ) + k 1 ( t ) ) , ( k 1 ( t ) k 2 ( t ) ) ] , H U ( E 3 , t ) = 2 diag [ ( k 2 ( t ) k 3 ( t ) ) , ( k 1 ( t ) k 3 ( t ) ) , ( k 1 ( t ) + k 2 ( t ) ) ] .
Proof. 
Evaluating the second variation of the Morse function given by Equation (10) on the set S c at an instant of time t, gives:
δ 2 U ( t ) S c = K ( t ) R , ( Σ × ) 2 R S c .
Evaluating Equation (21) at each of the four critical points, we get:
δ 2 U ( t ) I = k 1 ( t ) ( Σ 2 2 + Σ 3 2 ) + k 2 ( t ) ( Σ 3 2 + Σ 1 2 ) + k 3 ( t ) ( Σ 1 2 + Σ 2 2 ) , δ 2 U ( t ) E 1 = k 1 ( t ) ( Σ 2 2 + Σ 3 2 ) k 2 ( t ) ( Σ 3 2 + Σ 1 2 ) k 3 ( t ) ( Σ 1 2 + Σ 2 2 ) , δ 2 U ( t ) E 2 = k 1 ( t ) ( Σ 2 2 + Σ 3 2 ) + k 2 ( t ) ( Σ 3 2 + Σ 1 2 ) k 3 ( t ) ( Σ 1 2 + Σ 2 2 ) , δ 2 U ( t ) E 3 = k 1 ( t ) ( Σ 2 2 + Σ 3 2 ) k 2 ( t ) ( Σ 3 2 + Σ 1 2 ) + k 3 ( t ) ( Σ 1 2 + Σ 2 2 ) .
We evaluate the Hessian matrix evaluated for R S c by taking second partial derivatives of δ 2 U with respect to Σ i , i = 1 , 2 , 3 . This is obtained as:
H U ( R , t ) | R S c = 2 Σ i Σ j trace L ( t ) Σ × 2 i j
where L ( t ) = K ( t ) R . For R S c , we get:
L ( t ) = diag i ( t ) , where   i ( t ) = k i ( t ) R i i , i { 1 , 2 , 3 } ,
because the critical values R S c are diagonal matrices. In addition, tr ( L ( t ) ( Σ × ) 2 ) = ( 2 ( t ) + 3 ( t ) ) Σ 1 2 + ( 3 ( t ) + 4 ( t ) ) Σ 2 2 + ( 1 ( t ) + 2 ( t ) ) Σ 3 2 , which leads to the following expression for the Hessian matrices evaluated at these critical points:
H U ( R , t ) | R S c = 2 2 ( t ) + 3 ( t ) 0 0 0 3 ( t ) + 1 ( t ) 0 0 0 1 ( t ) + 2 ( t ) .
Substituting i ( t ) for i = 1 , 2 , 3 , based on Equation (23) evaluated at each of the critical points into Equation (24), leads to the Hessian matrices given explicitly by Equation (20) at these critical points. □
Equation (20) reveals that the Hessian of the Morse function evaluated at critical points in the set (16) depends on time because of K ( t ) ; 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 H U ( R , t ) for R S c are time-varying and may be positive, negative or even momentarily zero depending on the relative values of the k i ( t ) . The only critical point that has a positive definite Hessian and therefore a zero index for all time is the identity I SO ( 3 ) , which corresponds to the desired equilibrium state ( I , 0 ) TSO ( 3 ) SO ( 3 ) × so ( 3 ) . In summary, the time-varying positive diagonal gain matrix K ( t ) ensures that the non-minimum critical points of the Morse function that are in the set S c I , have time-varying indices.
Remark 1.
The index of a critical point (of the Morse function) is the number of negative eigenvalues of its Hessian, H U ( R , t ) , for R S c . If K ( t ) = K is constant, then the indices of I , E 1 , E 2 , and E 3 are 0, 1, 2 and 3, respectively with the minimum attained at R = I , given that k 1 > k 2 > k 3 > 0 . However, when K ( t ) is time-varying, the number of positive and negative eigenvalues of the Hessian at any of the three non-minimum critical points of the Morse function (i.e., any point in the set S c I ), may switch with time depending on K ( t ) . As the index values can vary with time for R S c I , the dimensions of stable and unstable manifolds associated with these critical points also switch with time. As can be seen from Equation (20), a switch in the index of one of these three critical points occurs when k i ( t ) = k j ( t ) for i j , i , j { 1 , 2 , 3 } . This results in discrete switching of the index values at these critical points depending on the instantaneous inequality constraint between the elements of the positive diagonal matrix K ( t ) . The indices 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 S ( E i ) is calculated as dim ( S ( E i ) ) = 6 Index ( E i ) , where 6 is the total dimension of the state-space TSO ( 3 ) SO ( 3 ) × so ( 3 ) . Therefore, the stable manifolds and their dimensions vary over time for the equilibrium points ( E i , 0 ) TSO ( 3 ) corresponding to the critical points E i S c I of U ( R , t ) .

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 ( I , 0 ) . It uses a particular design of the time-varying gains to obtain this result.
Theorem 1.
Consider a positive diagonal time-varying K ( t ) R 3 × 3 such that K ( t ) = K ¯ + K ˜ ( t ) where K ¯ , K ˜ ( t ) R 3 × 3 are diagonal and k i = k ¯ i + k ˜ i ( t ) > 0 , i = 1 , 2 , 3 , and k ˜ i ( t ) = k ˜ i ( t + T ) > 0 is C 1 continuous, non-negative, and time-periodic with period T. Consider the attitude control law for the rigid body given by:
τ = J Ω ˙ d + Ω d × J Ω L Ω ˜ ( Ω ˜ T L Ω ˜ ) ( 1 1 / p ) , Ω d = S K ( t ) ( R )   a n d   Ω ˜ : = Ω Ω d ,
where p ] 1 , 2 [ , L J 0 . This control law makes the state ( R , Ω ) = ( I , 0 ) almost globally asymptotically 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 Ω d ( t ) that is guaranteed to steer the attitude R ( t ) towards the identity attitude I. In the second step, the attitude dynamics is considered, where we formulate the control torque law τ ( t ) that forces the true angular velocity Ω ( t ) of the rigid body to follow the desired angular velocity Ω d ( t ) with finite-time stable (FTS) convergence.
Consider the polar Morse function on SO ( 3 ) given by
U K ¯ ( R ) = K ¯ , I R ,
which depends on the constant part of K ( t ) as defined in the statement. The time derivative of (26) is given by
U ˙ K ¯ = K ¯ , R Ω × = ( 1 / 2 ) K ¯ R R T K ¯ , Ω × = ( S K ¯ ( R ) ) T Ω = Ω T S K ¯ ( R ) ,
where S K ¯ ( R ) = vex ( K ¯ R R T K ¯ ) = i = 1 3 k ¯ i e i × R T e i and vex ( · ) : so ( 3 ) R 3 is the inverse of the cross-product operator map ( · ) × defined by Equation (2). A kinematic control law that leads to almost global asymptotically stable (AGAS) convergence of R to I SO ( 3 ) described by (1) is given by
Ω d = S K ( t ) ( R ) = i = 1 3 k i ( t ) ( e i × R T e i ) ,
where k i ( t ) = k ¯ i + k ˜ i ( t ) > 0 according to the properties of K ( t ) . Setting the true angular velocity equal to the desired angular velocity Ω d , and substituting (28) into the expression (27) for the time derivative of U K ¯ ( R ) , gives:
U ˙ K ¯ = ( S K ( t ) ( R ) ) T S K ¯ ( R ) = ( S K ¯ ( R ) ) T S K ¯ ( R ) + S K ˜ ( t ) ( R ) .
Simplifying (29) using (28) and the observation that the vectors ( e i × R T e i ) , i = 1 , 2 , 3 , are mutually orthogonal, leads to:
U ˙ K ¯ = i = 1 3 ( k ¯ i 2 + k ¯ i k ˜ i ( t ) ) e i × R T e i 2 = S K ¯ ( R ) 2 ( S K ¯ ( R ) ) T S K ˜ ( t ) ( R ) .
Given that both K ¯ is positive and K ˜ ( t ) is non-negative diagonal (i.e., k ¯ i > 0 , k ˜ i ( t ) > 0 ), Equation (30) leads to the conclusion that:
U ˙ K ¯ = i = 1 3 k ¯ i ( k ¯ i + k ˜ i ( t ) ) e i × R T e i 2 S K ¯ ( R ) 2 0 .
In inequality (31), the time derivative of the constant gain Morse function U ˙ K ¯ = 0 when R S c . The only (global) minimum of U K ¯ is at R = I , while E 1 and E 2 are saddle points with indices 1 and 2 respectively. The global maximum of U K ¯ over SO ( 3 ) is attained at E 3 . Therefore, with the kinematic control law (28), all trajectories on SO ( 3 ) that do not start on the stable manifolds of E 1 and E 2 , or at E 3 , converge to R = I . This leads to R = I being the AGAS equilibrium for this kinematic (velocity level) control system on SO ( 3 ) . In addition, applying Lemma 1 to inequality (31), we see that U ˙ K ¯ U K ¯ in the neighborhood N SO ( 3 ) of I SO ( 3 ) given by Equation (9). This leads to local exponential stability of the kinematic control law (28) at R = I .
The next step of this control scheme is to track the desired angular velocity profile given by the kinematic-level control law (28) 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 Ω ˜ : = Ω Ω d . Consider the attitude dynamics of the body given by the second of Equation (1), where J = J T 0 is the inertia matrix. Define the following energy-like Lyapunov function of the angular velocity tracking error:
V : = 1 2 Ω ˜ T J Ω ˜ = V ( Ω ˜ ) .
The time derivative of this Lyapunov function along the trajectories of (1) is given by:
V ˙ = Ω ˜ T ( J Ω × Ω + τ J Ω ˙ d ) .
Substituting the finite-time stable τ control law (25) into expression (33) for V ˙ and using the relation L J 0 results in,
V ˙ = ( Ω ˜ T L Ω ˜ ) 1 / p ( Ω ˜ T J Ω ˜ ) 1 / p V ˙ ( 2 V ) 1 / p .
Therefore, from (34) and [17], we conclude that Ω Ω d in finite time, with the settling time upper-bounded as follows:
T s V ( Ω ˜ 0 ) 1 ( 1 / p ) 2 1 / p ( 1 ( 1 / p ) ) = V 0 1 ( 1 / p ) 2 1 / p ( 1 ( 1 / p ) ) ,
where V 0 = V ( Ω ˜ 0 ) is the initial value of the Lyapunov function in (32) and Ω ˜ 0 is the initial tracking error in angular velocity. In summary, the control law (25) ensures FTS convergence of Ω to Ω d , which in turn ensures AGAS convergence of ( R , Ω ) to ( I , 0 ) according to the kinematic control law (28). □
For numerical simulation studies, this work considers a particular structure of K ( t ) given by:
K ( t ) = diag [ C 1 + a 1 cos ( ω 1 t + ϕ 1 ) 2 , C 2 + a 2 cos ( ω 2 t + ϕ 2 ) 2 , C 3 + a 3 cos ( ω 3 t + ϕ 3 ) 2 ] ,
where C i > 0 , a i > 0 , ω i is the oscillation frequency and ϕ i is an initial phase, for i = 1 , 2 , 3 . In Equation (36), as the diagonal elements are periodically modulated positive functions, the conditions k i ( t ) = k j ( t ) ; i j ; i , j { 1 , 2 , 3 } are satisfied at most at isolated instants in time for almost all choices of ( C i , ω i , ϕ i ) . Therefore, the relative ordering among the diagonal elements of K ( t ) changes repeatedly as time evolves. These changes lead to discrete switching of the indices of the three non-minimum critical points as explained in Remark 1 of Section 3. As a result, the stable manifolds of the unstable equilibria corresponding to these critical points E 1 , E 2 or E 3 have changing dimensions and changing structures, and the feedback system cannot settle into these stable manifolds for all time.

5. Numerical Simulation Results

In this section, a comparative set of numerical simulations with constant gain K and time-varying gain K ( t ) 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) [18], obtained by applying the discrete Lagrange–d’Alembert principle [19,20,21]. Consider an interval of time [ t 0 , T ] R + separated into N equal-length subintervals [ t n , t n + 1 ] for n = 0 , 1 , 2 , , l , with t l + 1 = T and Δ t = t n + 1 t n is the time step size. The discrete-time equations are:
( J Ω n ) × = 1 Δ t F n J J F n T , J = 1 2 tr [ J ] I 3 J , R n + 1 = R n F n , J Ω n + 1 = F n T ( J Ω n ) + Δ t τ n , τ n = τ ( R n , Ω n ) .
For the time-varying gains of the Morse function, we choose the K ( t ) as described in (36), with:
K ( t ) = 0.5 diag [ 0.55 + 0.2 cos ( 0.04 π t + π / 2 ) 2 , 0.52 + 0.15 cos ( 0.12 π t + π / 3 ) 2 , 0.5 + cos ( 0.2 π t + π / 4 ) 2 ] .
For the constant gain Morse function, the gains are selected as K = 0.5 diag [ 0.55 + 0.2 / 2 , 0.52 + 0.15 / 2 , 0.5 + 1 / 2 ] . The simulated time period is 150 s. The gain matrix for the dynamic level controller (25) is L = J 1 + 0.03 I 3 with p = 1.01 . The inertia tensor of the rigid body is J 1 = diag ( [ 3 4 5 ] ) kg·m2. Figure 1, Figure 2 and Figure 3 show comparative simulation results for constant K versus time-varying K ( t ) with initial attitudes of the rigid body given by R 0 = E 1 , R 0 = E 2 and R 0 = E 3 , respectively. The initial angular velocity is chosen as Ω 0 = [ 10 5 10 5 0 ] T rad / s for all three cases. Figure 1a, Figure 2a and Figure 3a show the principal rotation angle profiles for time-varying K ( t ) converging to zero (corresponding to identity attitude R = I 3 ), whereas with the constant K it remains trapped at the initial attitude R 0 = E 1 , R 0 = E 2 , R 0 = E 3 , respectively. This behavior arises because the time-varying K ( t ) induces discrete switching of the critical points of the Morse function, thereby preventing the system response from being trapped at the initial attitude, unlike in the constant K case. Figure 1b, Figure 2b and Figure 3b show the norm of angular velocity profiles, and Figure 1c, Figure 2c and Figure 3c shows the variation of norm of control torque. The small differences in the peak magnitudes of the control torque in Figure 1c, Figure 2c and Figure 3c are due to the selections of the diagonal entries of the time-varying K ( t ) and the inertia matrix J 1 . These 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. Conclusions

This work provides a continuous time-varying state dependent feedback attitude controller on TSO ( 3 ) based on Morse functions with time-varying gains. As a result, the stable manifolds of the undesirable equilibria for the feedback system of the rigid body are disrupted because the indices of the non-minimum critical points corresponding to these equilibrium points switch discretely in time. The only always stable equilibrium on TSO ( 3 ) is the identity attitude with zero angular velocity. Simulation results confirm that the time-varying Morse function can prevent the system response from “getting stuck" near the undesired equilibria of the feedback system and can achieve convergence to the identity attitude. Future work will extend these results to coordinated relative-attitude control for networks of unmanned aerial vehicles modeled as multi-agent rigid-body systems (MARBS). A key direction is the design of distributed, time-varying gain matrices that shape agent-wise Morse functions and prevent the formation of undesired equilibria in the MARBS network. Another planned future research topic in this direction, is to analyze MARBS with complex but more practical graph topologies of the communications network, such as for MARBS with nearest neighbor communication.

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.

Data Availability Statement

Data, including computer codes used for simulations reported in this paper, will be made available through the US NSF Public Access Repository (NSF PAR) as part of project reports for the projects under which this research was supported. This data will be publicly accessible.

Acknowledgments

The authors acknowledge insights provided by helpful discussions with Eric Butcher at the University of Arizona.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Bhat, S.; Bernstein, D. A Topological Obstruction to Continuous Global Stabilization of Rotational Motion and the Unwinding Phenomenon. Syst. Control Lett. 2000, 39, 63–70. [Google Scholar] [CrossRef]
  2. 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, Minneapolis, MN, USA, 14–16 June 2006. [Google Scholar] [CrossRef]
  3. Chaturvedi, N.; Sanyal, A.; McClamroch, N. Rigid-body attitude control. Control Syst. IEEE 2011, 31, 30–51. [Google Scholar] [CrossRef]
  4. Koditschek, D.E. The application of total energy as a Lyapunov function for mechanical control systems. Contemp. Math. 1989, 97, 131. [Google Scholar] [CrossRef]
  5. Eslamiat, H.; Wang, N.; Hamrah, R.; Sanyal, A.K. Geometric Integral Attitude Control on SO(3). Electronics 2022, 11, 2821. [Google Scholar] [CrossRef]
  6. 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), Toronto, ON, Canada, 10–12 July 2024; pp. 3049–3054. [Google Scholar] [CrossRef]
  7. 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), Denver, CO, USA, 8–10 July 2025; pp. 1198–1203. [Google Scholar] [CrossRef]
  8. Nazari, M.; Maadani, M.; Butcher, E.A.; Yucelen, T. Morse-Lyapunov-Based Control of Rigid Body Motion on TSE(3) via Backstepping. In Proceedings of the 2018 AIAA Guidance, Navigation, and Control Conference, Kissimmee, FL, USA, 8–12 January 2018. [Google Scholar] [CrossRef]
  9. Maadani, M.; Butcher, E.A. Pose consensus control of multi-agent rigid body systems with homogenous and heterogeneous communication delays. Int. J. Robust Nonlinear Control 2022, 32, 3714–3736. [Google Scholar] [CrossRef]
  10. Mathavaraj, S.; Butcher, E.A. Rigid-body attitude control, synchronization, and bipartite consensus using feedback reshaping. J. Guid. Control Dyn. 2023, 46, 1095–1111. [Google Scholar] [CrossRef]
  11. Butcher, E.A.; Spaeth, V. Decentralized Consensus Protocols on SO(4)N and TSO(4)N with Reshaping. Entropy 2025, 27, 743. [Google Scholar] [CrossRef] [PubMed]
  12. 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. Int. J. Robust Nonlinear Control 2015, 25, 3617–3640. [Google Scholar] [CrossRef]
  13. Dong, X.; Yu, B.; Shi, Z.; Zhong, Y. Time-varying formation control for unmanned aerial vehicles: Theories and applications. IEEE Trans. Control Syst. Technol. 2014, 23, 340–348. [Google Scholar] [CrossRef]
  14. 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]
  15. Maadani, M.; Butcher, E.A. 6-DOF consensus control of multi-agent rigid body systems using rotation matrices. Int. J. Control 2022, 95, 2667–2681. [Google Scholar] [CrossRef]
  16. Bohn, J.; Sanyal, A.K. Almost global finite-time stabilization of rigid body attitude dynamics using rotation matrices. Int. J. Robust Nonlinear Control 2016, 26, 2008–2022. [Google Scholar] [CrossRef]
  17. Bhat, S.; Bernstein, D. Finite-Time Stability of Continuous Autonomous Systems. SIAM J. Control Optim. 2000, 38, 751–766. [Google Scholar] [CrossRef]
  18. 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), Atlanta, GA, USA, 15–17 December 2010; pp. 5414–5419. [Google Scholar] [CrossRef]
  19. Marsden, J.; West, M. Discrete mechanics and variational integrators. Acta Numer. 2001, 10, 357–514. [Google Scholar] [CrossRef]
  20. Hairer, E.; Lubich, C.; Wanner, G. Structure-preserving algorithms for ordinary differential equations. In Geometric Numerical Integration, 2nd ed.; Springer Series in Computational Mathematics; Springer: Berlin/Heidelberg, Germany, 2006; Volume 31, pp. xviii+644. [Google Scholar] [CrossRef]
  21. Schmitt, J.M.; Leok, M. Properties of Hamiltonian variational integrators. IMA J. Numer. Anal. 2018, 38, 377–398. [Google Scholar] [CrossRef]
Figure 1. Comparative simulation results with time-varying and constant gain Morse functions with R 0 = E 1 . (a) Principal rotation angle; (b) Norm of angular velocity; (c) Norm of control torque.
Figure 1. Comparative simulation results with time-varying and constant gain Morse functions with R 0 = E 1 . (a) Principal rotation angle; (b) Norm of angular velocity; (c) Norm of control torque.
Vehicles 07 00143 g001
Figure 2. Comparative simulation results with time-varying and constant gain Morse functions with R 0 = E 2 . (a) Principal rotation angle; (b) Norm of angular velocity; (c) Norm of control torque.
Figure 2. Comparative simulation results with time-varying and constant gain Morse functions with R 0 = E 2 . (a) Principal rotation angle; (b) Norm of angular velocity; (c) Norm of control torque.
Vehicles 07 00143 g002
Figure 3. Comparative simulation results with time-varying and constant gain Morse functions with R 0 = E 3 . (a) Principal rotation angle; (b) Norm of angular velocity; (c) Norm of control torque.
Figure 3. Comparative simulation results with time-varying and constant gain Morse functions with R 0 = E 3 . (a) Principal rotation angle; (b) Norm of angular velocity; (c) Norm of control torque.
Vehicles 07 00143 g003
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

Sanyal, A.K.; Srinivasu, N. Time-Varying Feedback for Rigid Body Attitude Control. Vehicles 2025, 7, 143. https://doi.org/10.3390/vehicles7040143

AMA Style

Sanyal AK, Srinivasu N. Time-Varying Feedback for Rigid Body Attitude Control. Vehicles. 2025; 7(4):143. https://doi.org/10.3390/vehicles7040143

Chicago/Turabian Style

Sanyal, Amit K., and Neon Srinivasu. 2025. "Time-Varying Feedback for Rigid Body Attitude Control" Vehicles 7, no. 4: 143. https://doi.org/10.3390/vehicles7040143

APA Style

Sanyal, A. K., & Srinivasu, N. (2025). Time-Varying Feedback for Rigid Body Attitude Control. Vehicles, 7(4), 143. https://doi.org/10.3390/vehicles7040143

Article Metrics

Back to TopTop