Open access peer-reviewed chapter

Modeling and Attitude Control of Satellites in Elliptical Orbits

Written By

Espen Oland

Submitted: 01 March 2018 Reviewed: 20 July 2018 Published: 05 November 2018

DOI: 10.5772/intechopen.80422

From the Edited Volume

Applied Modern Control

Edited by Le Anh Tuan

Chapter metrics overview

1,636 Chapter Downloads

View Full Metrics

Abstract

The attitude determination and control system (ADCS) for spacecraft is responsible for determining its orientation using sensor measurements and then applying actuation forces to change the orientation. This chapter details the different components required for a complete attitude determination and control system for satellites moving in elliptical orbits. Specifically, the chapter details the orbital mechanics; perturbations; controller design; actuation methods such as thrusters, reaction wheels, and magnetic torquers; actuation modulation methods such as bang-bang, pulse-width modulation, and pulse-width pulse-frequency; as well as attitude determination using vector measurements combined with mathematical models. In sum, the work describes in a tutorial manner how to put everything together to enable the design of a complete satellite simulator.

Keywords

  • ADCS
  • attitude control
  • attitude estimation
  • thrusters
  • reaction wheels
  • magnetic torquers
  • elliptical orbits
  • PWM
  • PWPF
  • bang-bang
  • Madgwick filter
  • Sun vector model
  • magnetic field model
  • sliding surface control
  • quaternions
  • angular velocity

1. Introduction

The problem of developing attitude determination and control systems (ADCS) has received much attention in the last century with general books such as [1, 2, 3, 4], as well as description of individual ADCS designs for different satellites in works such as [5, 6, 7, 8]. While Refs. [1, 2] can be considered excellent foundation books within the topic of spacecraft modeling and control, there is a need for a more concise presentation of the attitude control problem and how this can be modeled in a simple manner, both not only as a tutorial for new researchers but also to give insight into the different components required for ADCS design drawing on ideas and results from previous works as mentioned above.

This chapter is an extension of [9] and builds on much of the previous work, as well as the research done through the HiNCube project as presented in [10, 11, 12]. This work considers the problem of designing a complete ADCS system comprising all the required components. Figure 1 shows the control structure and the required signal paths, giving an overview of the contents in this chapter, as each block is described in detail to put the reader in position to design their own ADCS system. The required sensors for this system are a magnetometer to measure the Earth’s magnetic field, a gyro to measure the angular velocity of the satellite, as well as Sun sensors for measuring the direction toward the Sun. Further, the mathematical models used together with sensor measurements to determine the attitude of the satellite requires a real-time clock, as the time and date are required to know the direction toward the Sun as well as what the magnetic field looks like at a given day and time. Comparing the sensor measurements with the mathematical models allows for the determination of the attitude of the satellite, something that is done using the Madgwick filter as presented in [13]. With an estimated attitude obtained using the Madgwick filter, the attitude can be controlled to point a sensor onboard the satellite in a desired direction, something that is solved in this chapter using a PD+ attitude controller, calculating the desired torques required in order to make the attitude and angular velocity errors go to zero. In order to create the desired moments, this chapter presents how this can be achieved using a number of different actuators, namely, magnetic torquers, reaction wheels, and thrusters. The orbital mechanics block describes how the satellite moves in its elliptical orbit, while the perturbing forces and moments block describe how the different perturbations affect the satellite. Simulations show the performance of the different methods and should put the reader in a position to simulate and design new attitude determination and control systems for satellites in elliptical orbits.

Figure 1.

This figure shows the different components required for modeling and controlling a satellite in an elliptical orbit and shows the main components required for creating a satellite simulator.

Advertisement

2. Mathematical modeling

2.1. Notation

This subsection is similar to the author’s previous works, e.g., [9, 14]. Let x ̇ = d x / dt denote the time derivative of a vector, while the Euclidean length is defined as x = x Τ x . Superscript denotes frame of reference for a given vector. The rotation matrix is denoted R a c SO 3 = R R 3 × 3 : R Τ R = I det R = 1 , which rotates a vector from frame a to frame c and where I denotes the identity matrix. The inverse rotation is found by taking its transpose, such that R c a = R a c Τ . The angular velocity of frame c relative to frame a referenced in frame e is denoted ω a , c e , and angular velocities can be added together as ω a , f e = ω a , c e + ω c , f e (cf. [15]). The derivative of the rotation matrix is defined as R ̇ a c = R a c S ω c , a a where S denotes the cross product operator, which is defined such that for two vectors v 1 , v 2 R 3 , S v 1 v 2 = v 1 × v 2 , S v 1 v 2 = S v 2 v 1 , S v 1 v 1 = 0 , and v 1 Τ S v 2 v 1 = 0 .

Quaternions can be used to parameterize the rotation matrix, where q c , a S 3 = q R 4 : q Τ q = 1 denotes the quaternion representing a rotation from frame a to frame c through the angle of rotation ϑ c , a around the axis of rotation k c , a . The inverse quaternion is defined as q a , c = η c , a ε c , a Τ Τ , also sometimes denoted as q . A quaternion comprises a scalar and a vector part, where η c , a denotes the scalar part, while ε c , a R 3 denotes the vector part. This allows the rotation matrix to be constructed using quaternions as R a c = I + 2 η c , a S ε c , a + 2 S 2 ε c , a . Composite quaternions can be found through quaternion multiplication as q c , e = q c , a q a , e = T q c , a q a , e with

T q c , a = η c , a ε c , a Τ ε c , a η c , a I + S ε c , a . E1

The use of the quaternion product ensures that the resulting quaternion maintains the unit length property. The quaternion kinematics is defined as

q ̇ c , a = 1 2 q c , a 0 ω c , a a = 1 2 T q c , a 0 ω c , a a . E2

For attitude control, several different frames are needed:

Inertial: The Earth-centered inertial (ECI) has its origin in the center of the Earth, where the x i axis points toward the vernal equinox and the z i points through the North Pole, while y i completes the right-handed orthonormal frame. The inertial frame is denoted by F i .

Orbit: The orbit frame has its origin in the center of mass of the satellite (cf. [16], p. 479). The e r axis coincides with the radius vector r i R 3 , which goes from the center of the Earth to the center of mass in the satellite. The e h axis is parallel to the orbital angular momentum vector, pointing in the normal direction of the orbit. The e θ completes the right-handed orthonormal frame where the vectors can be described as e r = r i r i , e θ = e h × e r , and e h = h h where h = r i × r ̇ i . The orbit frame is denoted by F o .

Body: The body frame has its origin in the center of mass of the satellite, where its axes coincide with the principal axes of inertia. The body frame is denoted by F b .

Desired: The desired frame can be defined arbitrarily to achieve any given objective (cf. [17]). The desired frame is denoted by F d .

2.2. Orbital mechanics

This section describes how the orbit frame can be related to the inertial frame through the six classical orbital parameters, and for more details, the reader is referred to [1]. Specifically, the objective with this subsection is to find the radius, velocity, and acceleration vector of the orbit, as well as its angular velocity and acceleration. From well-known orbital mechanics, the six classical parameters can be defined as the semimajor axis a , the eccentricity e , the inclination i , the right ascension of the ascending node Ω , the argument of the perigee ω , and the mean anomaly M . The distance to the apogee and perigee from the center of the Earth can be defined, respectively, as r a and r p , allowing the semimajor axis to be found as a = r a + r p 2 and the eccentricity of the orbit as e = r a r p r a + r p , while the mean motion can be found from n = μ a 3 . Here, μ = GM Earth , where G is the gravitational constant, while M Earth is the mass of the Earth. With knowledge of the mean motion, the mean anomaly can be found as M = n t t 0 = ψ e sin ψ where ψ is the eccentric anomaly, t is the time, and t 0 is the time when passing the perigee. To properly describe where in the orbit the satellite is located, the true anomaly can be found as θ = cos 1 cos ψ e 1 e cos ψ , while its derivative can be found as θ ̇ = n 1 + e cos θ 2 1 e 2 3 2 ([18], p. 42). When running a simulation, it is desirable to have a continuously increasing true anomaly, while the direct method will map the angle between 0 and 180 ° . Instead, by integrating the derivative overtime, a smooth true anomaly can be found that increases continuously. The eccentric anomaly, however, cannot be found analytically, but can be found through an iterative algorithm as described in ([1], p. 26) ψ k t = M t + e sin ψ k 1 t , where k is the iteration number. This algorithm is valid as long as 0 < e < 1 , which holds for elliptical orbits. From these calculations, the rotation matrix from inertial frame to orbit frame can now be constructed as

R i o = cos ω + θ cos Ω cos i sin ω + θ sin Ω cos ω + θ sin Ω + sin ω + θ cos i cos Ω sin ω + θ sin i sin ω + θ cos Ω cos i sin Ω cos ω + θ sin ω + θ sin Ω + cos ω + θ cos i cos Ω cos ω + θ sin i sin i sin Ω sin i cos Ω cos i . E3

The radius, velocity, and acceleration vector can be defined in the orbit frame, respectively, as ([1], pp. 26–27)

r o = a cos ψ ae a sin ψ 1 e 2 0 Τ , E4
v o = a 2 n r sin ψ a 2 n r 1 e 2 cos ψ 0 Τ , E5
a o = a 3 n 2 r 2 cos ψ a 3 n 2 r 2 1 e 2 sin ψ 0 Τ , E6

where r = r i is the length of the radius vector. Each of these vectors can be rotated to the inertial frame using Eq. (3), such that r i = R i o r o , v i = R o i v o , and a i = R o i a o . The angular velocity of the orbit frame relative to the inertial frame can be found as ω i , o i = r i × v i r i Τ r i , while the angular acceleration can be found through differentiation as

ω ̇ i , o i = r i × a i r i Τ r i 2 r i × v i v i Τ r i r i Τ r i 2 . E7

In order to implement the orbital mechanics in, e.g., a Simulink framework, the required input to the subsystem would be the time ( t ). Further, the orbital parameters must be defined as given in Table 1 and can be changed depending on the orbit. These constants allow for the calculations of the eccentricity ( e ), the semimajor axis ( a ), and mean motion ( n ). With the mean motion, the mean anomaly ( M ) can be found and used to approximate the eccentric anomaly ( ψ ) using the iterative algorithm presented above. The rate of change of the true anomaly ( θ ̇ ) can also be found and by integration enables the calculation of true anomaly ( θ ). All these values allow for calculating the rotation matrix from the orbit frame to the inertial frame ( R o i ), the radius vector ( r o ), the velocity vector ( v o ), the acceleration vector ( a o ), angular velocity ( ω i , o i ), and angular acceleration vector ( ω ̇ i , o i ). Hence, all the outputs from this subsystem can easily be found following this procedure and will be used in several other subsystems.

Parameter Value Unit
G 6.67408 10 11 m 3 kg 1 s 2
M Earth 5.9742 10 24 kg
r a R e + 1200 km
r p R e + 800 km
R e 6378 km
i 75 °
Ω 0 °
ω 0 °

Table 1.

Parameters required for calculation of the orbital dynamics.

Advertisement

3. Attitude dynamics and control

3.1. Attitude dynamics

The attitude dynamics can be derived with the basis in Euler’s moment Equation ([1], p. 95). The angular momentum of a rigid body in the body frame is given as

h b = J ω i , b b , E8

where J R 3 x 3 is the inertia matrix, while ω i , b b R 3 is the angular velocity of the body frame relative to the inertial frame. The angular momentum can be found in the inertial frame as

h i = R b i h b . E9

The rate of change of angular momentum is equal to the total torque, such that τ i = h ̇ i . Hence, by differentiating Eq. (9), it is obtained that

τ i = h ̇ i = R b i S ω i , b b h b + R b i h ̇ b , E10

which can be written in the body frame by using Eq. (8) as τ b = S ω i , b b J ω i , b b + J ω ̇ i , b b , where the inertia matrix is assumed to be constant. Decomposing the total torque into an actuation component and a perturbing component, τ b = τ a b + τ p b , allows the rotational dynamics to be written as

J ω ̇ i , b b = S ω i , b b J ω i , b b + τ a b + τ p b , E11

where τ a b R 3 denotes the actuation torques (e.g., output from reaction wheels), while τ p b R 3 denotes the perturbing torques (e.g., gravity torque). Further, by using quaternion representation, the update law for the quaternion representing the attitude of the body frame relative to the inertial frame can be written as

q ̇ i , b = 1 2 T q i , b 0 ω i , b b . E12

Hence, Eqs. (11) and (12) serve as governing equations describing the attitude and angular velocity of the satellite. The inputs that affect these values are the perturbation and actuation torques, where the latter will be found in the following sections.

3.2. Error dynamics

From Euler’s moment equation, the angular acceleration is defined relative to the inertial frame. For attitude control, it is often more interesting controlling the attitude and angular velocity relative to the orbit frame. For that reason, the angular velocity of the body frame relative to the orbit frame can be found as ω o , b b = ω i , b b R i b ω i , o i , which can be differentiated as

J ω ̇ o , b b = S ω i , b b J ω i , b b + τ a b + τ p b + JS ω i , b b R i b ω o , i i JR i b ω ̇ i , o i E13

giving a description of the attitude dynamics relative to the orbit frame. It is also possible to find the error dynamics, to enable tracking of a desired attitude and angular velocity. Let q o , d , ω o , d d , ω ̇ o , d d L denote a desired quaternion, angular velocity, and acceleration; then, the quaternion and angular velocity error can be found as

q d , b = q d , o q o , b , E14
ω d , b b = ω o , b b R d b ω o , d d , E15

with the kinematics as

η ̇ d , b = 1 2 ε d , b Τ ω d , b b , E16
ε ̇ d , b = η d , b I + S ε d , b ω d , b b . E17

The angular acceleration error can be found by differentiating Eq. (15) as

J ω ̇ d , b b = S ω i , b b J ω i , b b + τ a b + τ p b + JS ω i , b b R i b ω o , i i JR i b ω ̇ i , o i + JS ω o , b b R d b ω o , d d JR d b ω ̇ o , d d . E18

Hence, the control objective can be defined as that of making q d , b ω d , b b 0 0 , which will make the satellite point in a desired direction and move with a desired angular velocity.

3.3. PD+ attitude controller

Takegaki and Arimoto [19] proposed in 1981 a simple method for position control of robots, something that was extended by [20] to enable trajectory tracking. The so-called PD+ controller has been applied for spacecraft by [21, 22] showing good results. The author has applied this method in previous works such as [23, 24].

In order to design a PD+ attitude controller, let a Lyapunov function candidate be chosen as V = 1 2 ω d , b b Τ J ω d , b b + k p 1 η d , b 2 + k p ε d , b Τ ε d , b where k p is a positive scalar gain. The derivative is found by using Eqs. (16)(18) as

V ̇ = k p ε d , b Τ ω d , b b + ω d , b b Τ S ω i , b b J ω i , b b + τ a b + τ p b + JS ω i , b b R i b ω o , i i JR i b ω ̇ i , o i + JS ω o , b b R d b ω o , d d JR d b ω ̇ o , d d . E19

A PD+ attitude control law can now be chosen as

τ d b = JR d b ω ̇ o , d d JS ω o , b b R d b ω o , d d + JR i b ω ̇ i , o i JS ω i , b b R i b ω o , i i τ p b + S ω i , b b J ω i , b b k p ε d , b k d ω d , b b , E20

where k d is another positive scalar gain and τ d b denotes the desired torque required to make the attitude and angular velocity errors go to zero. Assuming no actuator dynamics, i.e., τ a b = τ d b , and then by inserting Eq. (20) into Eq. (19), it is obtained that V ̇ k d ω d , b b 2 , which is negative semidefinite. By applying the Matrosov theorem (cf. [24]), it can be shown that the origin ( ε d , b , ω d , b b ) = ( 0 , 0 ) is uniformly asymptotically stable.

The inputs to the control law (Eq. 20) are the desired states q o , d , ω o , d d , and ω ̇ o , d d , which are to be defined by the reader, e.g., as part as a guidance block depending on the mission objective. The inertia matrix ( J ) is assumed to be known, while the angular velocity vector between the body frame and orbit frame ( ω o , b b ) can be found as described above. The other angular velocities are found from the orbital mechanics, while the rotation matrices are found as composite rotations, e.g., R i b = R o b R i o , or by using the relationship between the quaternions and rotation matrices directly (cf. Section 2A). The error quaternion and angular velocity are found from Eqs. (14) and (15), while the perturbing torques will be described in the following section.

Advertisement

4. Perturbing torques

There are different kinds of perturbing torques, such as gravity torque, aerodynamic torque, magnetic field due to the electronics inside the satellite, as well as solar radiation torque. This section only considers the gravity torque. In [16], p. 147, the gravity torque is defined as

τ g b = 3 GM Earth r 5 r i × Jr i , E21

where the terms have previously been defined. As can be seen from this equation, non-diagonal inertia matrices will induce gravitational torques to align the satellite with the gravity field. This is also sometimes used for passive control, using e.g., a gravity boom to ensure that one side of the satellite is always facing the Earth. For this chapter, the perturbing toque is set equal to the gravity torque such that τ p b = τ g b .

Advertisement

5. Actuators

The control signal must be mapped to an actuator that must generate the desired torque. With limitations in actuation, the saturation must be modeled in order to obtain realistic results when simulating attitude control. This section considers three types of actuators commonly used for spacecraft attitude control: magnetic torquers, reaction wheels, and thrusters.

5.1. Magnetic torquers

Magnetic torquers operate by creating a local magnetic field that interacts with the Earth’s magnetic field. In simple terms, magnetic torques can be explained as that of a compass needle. By applying current through a coil, a local magnetic field is created, which will try to align itself with the Earth’s magnetic field. This allows the attitude of a spacecraft to be changed and is a very popular approach for small satellites, e.g., cubesats. One of the drawbacks or challenges with magnetic actuation lies in the fact that the Earth’s magnetic field goes from the North Pole to the South Pole as shown in Figure 2.1 As can be seen, when the satellite crosses the North Pole, there will be mainly a downward magnetic field component, reducing the possibility of actuation to only two axes, and similarly along the equator. This subsection is based on [12] and will describe how to model magnetic torquers and how it can be applied for attitude control. A magnetic torquer produces a magnetic torque by applying a current through a coil, which can be expressed as [2].

τ m b = S m b b b , E22

where m b = m x m y m z Τ = NA i x i y i z Τ is the induced magnetic field, N is the number of turns of the coils, i is the current around a given axis, and A is the area of the coils. The Earth’s magnetic field is represented through the vector b b , meaning that to use magnetic actuation for attitude control, a good model of the Earth’s magnetic field is needed.

Figure 2.

Magnetic field of the Earth visualized using the IGRF model. The control torque using magnetic torquers is always perpendicular to the magnetic field, such that a the poles, only roll, and pitch control are available, while at the equator, only pitch and yaw control is available [25].

From a control point of view, the physical parameters A and N are defined when the spacecraft is designed, such that the controller needs to dictate which currents that must be sent to the torquers in order to get a desired torque. This means that Eq. (22) must be inverted with regard to m b , which is not straightforward due to the cross product, meaning that you obtain rank 2 when inverting the right-hand side, losing information about one of the axes. To that end, an approximation to inverting this equation is given in [25].

m b = S b b τ d b b b 2 , E23

enabling the currents to be found as

i x i y i z Τ = 1 NA m x m y m z Τ . E24

It is here assumed that all three torquers are identical, but depending on satellite configuration, there might be differences in the number of turns and areas. Hence, the desired torque τ d b can be used to find the magnetic moment m b in Eq. (23) and solved for the currents and applied resulting in the actuation torque in Eq. (22). Hence, the control law (Eq. 20) can be mapped to a desired magnetic moment (Eq. 23), which then can be used to find the desired current to each of the three coils. Then, the limits in current will dictate the maximum magnetic moment that can be generated.

Consider the HiNCube satellite as shown in Figure 3. The cubesat comprises three orthonormal magnetic torquers with an area A = 0.00757 m 2 and with a maximum current of 47.27 mA and N = 100 turns. This gives a maximum magnetic moment of m max = 0.03578 mA 2 . Hence, an implementation of using magnetic torquers for attitude control would encompass mapping the output from the control law to a desired magnetic moment using Eq. (23) and then imposing the maximum magnetic moment on each axis, before finding the resulting actuation torque using Eq. (22). Note that to ensure sign correctness due to the projection, the actuation torque can be found as

τ x , a τ y , a τ z , a Τ = sign τ x , d τ x , m sign τ y , d τ y , m sign τ z , d τ z , m Τ , E25

where τ a b = τ x , a τ y , a τ z , a Τ , τ d b = τ x , d τ y , d τ z , d Τ , and τ m b = τ x , m τ y , m τ z , m Τ .

Figure 3.

Magnetic torquers on the HiNCube satellite (shown in brown).

To show the performance of magnetic torquers, consider again the HiNCube satellite, which had an inertia matrix of J = 1.67 10 −3 I kg m 2 . Consider the problem of making rotating 90° from an initial quaternion q o , b = 0 0 0 1 Τ to q o , d = 1 0 0 0 Τ . The gains for the PD+ controller are set k p = 1 10 5 and k d = 5 10 3 , and the satellite is assumed to have an orbit of r p = 500 km and r a = 600 km, with inclination of 75 ° . Figure 4 shows the attitude, angular velocity, and actuation torque. It is evident that magnetic torquers produce very low torque, such that it takes a very long time to change the attitude of the spacecraft (about 1 h). To some extents, this can be improved by being in a lower orbit where the magnetic field is stronger or by using larger coils with higher currents. Also, note that the actuation signal varies in strength as a function of time, depending on the orbital position of the satellite.

Figure 4.

Quaternion error, angular velocity error, and actuation torque using magnetic torquers.

5.2. Reaction wheels

Another way of changing the attitude of a satellite is through reaction wheels. Reaction wheels are based on the principle of Newton’s third law: When one body exerts a force on a second body, the second body simultaneously exerts a force equal in magnitude and opposite in direction on the first body. This means that by spinning a reaction wheel in one direction, the satellite will rotate in the other direction. Mounting three reaction wheels in an orthogonal configuration enables three-axis attitude control of spacecraft. From Newton’s third law, the momentum generated by the reaction wheels will have opposite sign of the momentum of the satellite, such that h ̇ i = h ̇ w i where h ̇ w i is the momentum production by the reaction wheels, h ̇ i is the momentum acting on the satellite, and τ w b . By employing Euler’s moment equation similarly as in Section 3, the torque generated by the reaction wheels can be found by differentiating h w i = R b i h w b with h w b = J w w w b where ω w b is the angular velocity of the reaction wheels and J w denotes their inertia. This gives

τ a b = h ̇ w b S ω i , b b h w b , E26

where τ w b = h ̇ w b is the torque generated by the reaction wheels. Now, consider a set of three orthonormal reaction wheels, where one produces torques around the x -axis, one around the y -axis, and one around the z -axis of the body frame. Then, the PD+ control law dictates a desired torque, τ d b , which shall be achieved by the reaction wheels. To that end, the torque by the reaction wheel can be rewritten as τ w b = τ d b S ω i , b b h w b , where τ w b must be bounded by the motor torque limit, while the angular momentum will be bounded as a function of maximum rotational speed. After imposing the torque and speed constraints, the angular momentum of the reaction wheels is found by integrating h ̇ w b allowing the actuation torque to be calculated using Eq. (26).

Consider the HiNCube satellite again, where it is possible to use three small reaction wheels as described in [11] where the main idea is to place most of the mass away from the center as shown in Figure 5. The inertia of an individual reaction wheel was found to be J w = 1.46 10 5 kg m 2 , and by assuming a maximum rotation speed of 13,700 rpm with maximum torque of τ max = 0.0047 Nm, the maximum momentum generated by the reaction wheels is found as h max = J w ω w = 1.46 10 5 13700 2 π 60 = 1.52389 10 6 . Now, consider the same simulation as when using the magnetic torquers, where the gains for the PD+ controller is changed to k p = k d = 2 and the reaction wheels has the limits as defined above. Figure 6 shows the simulation results, where it is obvious that by using reaction wheels, the satellite is able to change its orientation after about 80 s. To some extent, this can be credited to the higher gains, but it lies mainly with the better actuation system that is able to produce higher torque than the reaction wheels. From the figure, the reaction wheels quickly go into saturation of 13 , 700 RPM, where the angular velocity also goes into saturation. As the quaternion error goes toward zero, the reaction wheel despin, reducing the angular velocity and the control objective, is completed.

Figure 5.

Example design of a reaction wheel for cubesats (dimensions are in mm) [11].

Figure 6.

Quaternion error, angular velocity error, and wheel speeds when using reaction wheels for attitude control.

5.3. Thrusters

The third kind of actuator that will be studied is using reaction control thrusters. This section presents how to map the control signal (Eq. 20) to four thrusters used for attitude control. Let the location of each thruster be denoted by r i b = r x r y r z Τ , and let them have an azimuth and an elevation angle described by χ and γ . Then, the torque produced by a given thruster can be found as [1], p. 262

τ i b = r i b × f i b = r y sin χ cos γ r z sin γ r z cos γ cos χ r x cos γ sin χ r x sin γ r y cos γ cos χ f i , E27

where f i denotes the total thrust from the ith thruster. Given the thruster configuration defined in Table 2, let the vector of thruster signals be denoted u = f 1 f 2 f 3 f 4 Τ , and then the torque can be found as τ a b = Bu with

B = 2 5 2 5 2 5 2 5 2 4 2 4 2 4 2 4 2 4 2 4 2 4 2 4 . E28
Thruster Elevation ( γ ) Azimuth ( χ ) r x r y r z
f 1 45 90 −0.5 −0.45 −0.05
f 2 135 90 −0.5 −0.45 0.05
f 3 −45 90 −0.5 0.45 −0.05
f 4 −135 90 −0.5 0.45 0.05

Table 2.

Thruster configuration.

Given a desired torque from the PD+ control law, it must be mapped to the desired thruster firings, such that the combination of thrusters produces the desired torque. To that end, there are several different modulation methods that can be applied, ranging from a simple bang-bang modulation to more sophisticated pulse-width pulse-frequency modulation. This section will give an introduction to the different methods and detail how they can be implemented. In general the desired torque can be mapped to the desired thruster firings as u d = B τ d b where denotes the Moore-Penrose pseudoinverse and u d = u 1 u 2 u 3 u 4 Τ denotes the magnitude of each of the thrusters.

  1. Bang-bang modulation: The easiest approach to thruster firings is bang-bang modulation, where the thruster is fully actuated as long as the ith signal of u d is above zero, such that

    f i = f max if u i > 0 0 if u i 0 , E29

    where f max denotes the maximum available thrust from the ith thruster. After applying bang-bang modulation, the vector u can be constructed allowing the actuator torque to be found as τ a b = Bu .

  2. Bang-bang modulation with dead zone: One of the major drawbacks by using simple bang-bang modulation is when the tracking error has converged to zero, where the thruster firings will continue to maintain the desired attitude. Sensor noise is another source that leads to continuous firings, quickly spending all the propellant. To that end, bang-bang modulation can be augmented with a dead zone, giving

    f i = f max if u i > D 0 if u i D , E30

    where D > 0 denotes the dead zone. By properly selecting a suitable dead zone enables the thrusters to avoid firing when close to the equilibrium point.

  3. Pulse-width modulation: Another approach that is often used for thruster firings is by using pulse-width modulation (PWM), where an analogue signal (desired torque) can be mapped to discrete signals using PWM. Instead of changing the thrust level, the duration of the pulses can be changed, leading to a pulse that is proportional to the torque command from the PD+ controller. A simple way of achieving this is by using the intersective technique, which uses a sawtooth signal that is compared to the control signal. When the sawtooth is less than the control signal, the PWM signal is in a high state and otherwise in a low state. This makes it possible to go from continuous control signal to a discrete representation which can be used for thruster firings. Figure 7 shows how to achieve the PWM signal, enabled through a simple comparison of the two signals.

  4. Pulse-width pulse-frequency modulation: In addition to controlling the width of the pulse as in PWM, it is also possible to control the frequency of the pulse—something that is done through pulse-width pulse-frequency (PWPF) modulation ([1], p. 265) (Figure 8). The modulation approach comprises a lag filter and a Schmitt trigger as shown in Figure 9. As long as the input to the Schmitt trigger is below U on , the output is kept at zero and must be larger than U on K to produce an output, where K is a DC gain, τ is the time constant, U on and U off are the on and off limits for the Schmitt trigger, while U m is the maximum output. Much research has been performed on improving PWPF modulation, and in [26], the authors propose the following settings (cf. Figure 9): 2 < K < 6 , 0.1 < τ < 0.5 , U on > 0.3 , U off < 0.8 U on , and U m = 1 .

  5. Simulations of thruster modulations: Consider a satellite with an inertia matrix as

    J = 0.5 0.2 0.1 0.2 0.5 0.2 0.1 0.2 0.5 , E31

    where the objective is to perform a yaw maneuver of 90 ° using four thrusters with 0.1 N force, with a specific impulse of 200 s. Figure 10 shows the attitude and angular velocity vectors when using bang-bang modulation, where the satellite is able to make the errors go to zero. However, due to the modulation, the thrusters will continue firing as shown in Figure 11. To that end, consider the bang-bang modulation with dead zone. Let the dead zone be chosen as D = 0.05 , and then the satellite obtains an accuracy as shown in Figure 12 where there is a small offset from the origin which is proportional to the dead zone. On the other hand, the thruster firings are much less prone to do continuous firings as shown in Figure 13.

Figure 7.

Thruster configuration. The left subfigure shows the definition of azimuth and elevation angles used to dictate the orientation of the thruster, while the right subfigure shows a satellite with thrusters placed and oriented as given in Table 2.

Figure 8.

Achieving pulse-width modulated signals for thruster firings.

Figure 9.

Pulse-width pulse-frequency modulation.

Figure 10.

Attitude control using thrusters with bang-bang modulation.

Figure 11.

Thruster firings when using bang-bang modulation.

Figure 12.

Attitude control using thrusters with bang-bang modulation with dead zone.

Figure 13.

Thruster firings when using bang-bang modulation with dead zone.

Now, consider pulse-width modulation. Let the sawtooth signal have an amplitude of 1 and a frequency of 1 Hz. Then, the attitude and angular velocity error is obtained as shown in Figure 14, while the thruster firings are shown in Figure 15. It is possible to tune on sawtooth frequency to improve the performance.

Figure 14.

Attitude control using thrusters with PWM modulation.

Figure 15.

Thruster firings when using PWM modulation.

The final scenario is using PWPF modulation, where the parameters are chosen as K = 3 , τ = 0.2 , U on = 0.35 , and U off = 0.28 . Figure 15 shows the attitude and angular velocity, which go close to zero, while the thruster firings are shown in Figure 16, which is able to constrain the amount of thruster firings, and therefore propellant.

Figure 16.

Attitude control using thrusters with PWPF modulation.

For satellite control using thrusters, propellant is a critical resource that must not be wasted. To that end it is desirable to limit the amount of propellant while at the same time obtain good pointing accuracy (Figure 17). With the basis in Tsiolkovsky’s rocket equation, the propellant consumption during thruster firings can be found as m propellant = 0 t f I sp g dt where f is the force from one of the thrusters and I sp is the specific impulse, while g = 9.81 m/s 2 is the acceleration due to gravity. Figure 18 shows a comparison between the different modulation methods, where it is evident that the PWPF method allows for the least amount of propellant while obtaining close to acceptable performance. The bang-bang modulation will continue spending propellant until running out of fuel but on the other hand obtains the best tracking performance.

Figure 17.

Thruster firings when using PWPF modulation.

Figure 18.

Propellant consumption of the different modulation methods.

Advertisement

6. Attitude determination

As a preliminary step before trying to estimate the attitude of the satellite, some knowledge of measurement vectors must be known, i.e., what is the direction toward the Sun and how does the magnetic field vector look like at a given position. There are several other quantities that can be measured to obtain the attitude, where star trackers are known to be the most accurate. For the reader to obtain insight into using multiple measurements and combine it to find the attitude, this work presents a Sun vector model and a simplified magnetic field model that can be used for simulation purposes.

6.1. Sun vector model

To find the direction toward the Sun, there are several models that can be applied. The simplest would be to divide a circle into 365 days and have a vector always point toward the Sun. Then, by knowing which day it is, it is straightforward to find the direction toward the Sun. This approach would be coarse, such that more accurate models exist. For example, the Sun vector model in [3], pp. 281–282, has an accuracy of 0.01 and is valid until 2050. First, the time and date must be converted into the Julian date as [3], p. 189.

JD = 367 yr INT 7 yr + INT mo + 9 12 4 + INT 275 mo 9 + d + 1,721,013.5 + s 60 + min 60 + h 24 , E32

where a real truncation is denoted by INT and the year, month, day, hour, minute, and second are denoted by yr , mo , d , h , min , s . If the day contains a leap second, 61 s should be used instead of 60 . This gives the Sun vector model as

T UT 1 = JD 2,451,545.0 36,525 , E33
λ M = 280.460 + 36,000.771 T UT 1 , E34
M = 357.5277233 + 35,999.05034 T UT 1 , E35
λ ecliptic = λ M + 1.914666471 sin M + 0.019994643 sin 2 M , E36
ε = 23.439291 0.0130042 T UT 1 , E37
s o = R i o cos λ ecliptic cos ε sin λ ecliptic sin ε sin λ ecliptic . E38

Here, the number of Julian centuries is denoted by T UT 1 , the mean longitude of the Sun is denoted by λ M , the mean anomaly for the Sun is denoted by M , the ecliptic longitude is denoted by λ ecliptic , and the obliquity of the ecliptic is denoted by ε , while the Sun vector in orbit frame is denoted by s o .

6.2. Magnetic field model

Several different geomagnetic models can be applied for attitude determination in conjunction with a magnetometer. The most basic are simple dipole models [27], while more advanced are, e.g., the chaos model or the 12th generation IGRF model [28], which is the most commonly used model for attitude determination. This section presents the simple dipole model by [27], which can be described by the magnetic field vector in orbit frame as

m o = μ f a 3 cos ω 0 t sin i cos i 2 sin ω 0 t sin i Τ , E39

where the time measured from passing the ascending node of the orbit relative to the geomagnetic equator is denoted by t and the dipole strength is denoted μ f = 7.9 10 15 Wb-m, while ω 0 = ω i , o i denotes the angular speed of the orbit. For a real application, the reader is recommended to apply the IGRF model, which is available in Simulink inside the Aerospace Toolbox, as C++ implementation2 or using Python.3

6.3. Attitude determination using the Madgwick filter

The objective of attitude determination is to find what direction the satellite is pointing. In its core, it mainly requires two vector measurements and two mathematical models that can be compared and used to find the attitude. There are several different kinds of filters applied for attitude estimation, such as the Triad method [29], the Kalman filter [30], or the Mahony filter [31]. The Madgwick filter by [13] has shown good results in attitude estimation based on IMU measurements and is commonly applied in drone applications. The main idea by the filter is to use gradient descent in combination with the complementary filter to fuse sensor data together to produce an estimated quaternion. This section presents an application of the Madgwick filter by using measurements of the Sun vector and the magnetic field vector as well as the acceleration vector (gravity) and shows how to fuse that data together to estimate the attitude of a satellite in an elliptical orbit.

Let the quaternion estimate be denoted by q ̂ = q 1 q 2 q 3 q 4 Τ . The measured acceleration, Sun vector, and magnetic field vectors can be defined, respectively, as a b , s b , and m b and can be combined with the mathematical models of the acceleration, Sun vector, and magnetic field vector given in Eqs. (6), (38), and (39) to estimate the attitude. Here, the current estimate is denoted by subscript k , while the previous estimate is denoted by k 1 . Let the objective function be

F = f q ̂ k 1 , a o a b f q ̂ k 1 , s o s b f q ̂ k 1 , m o m b , E40

where the objective is found in an estimated quaternion that minimizes this function, something that can be achieved by using gradient descent. The Jacobian matrix can be found as

J = J q q ̂ k 1 a o J q q ̂ k 1 s o J q q ̂ k 1 m o E41

and allows the gradient to be found as f = J Τ F . Now, let a vector in the orbit frame obtained from a mathematical model be denoted by z o = o x o y o z Τ and a vector in the body frame obtained through measurement be denoted by z b = b x b y b z Τ . Then, the functions f q ̂ k 1 z o z b and J q q ̂ k 1 z o are given by

f q ̂ k 1 , z o z b = 2 o x 0.5 q 3 2 q 4 2 + 2 o y q 1 q 4 + q 2 q 3 + 2 o z q 2 q 4 q 1 q 3 b x 2 o x q 2 q 3 q 1 q 4 + 2 o y 0.5 q 2 2 q 4 2 + 2 o z q 1 q 2 + q 3 q 4 b y 2 o x q 1 q 3 + q 2 q 4 + 2 o y q 3 q 4 q 1 q 2 + 2 o z 0.5 q 2 2 q 3 2 b z , E42
J q q ̂ k 1 z o = 2 o y q 4 2 o z q 3 2 o y q 3 + 2 o z q 4 4 o x q 3 + 2 o y q 2 2 o z q 1 4 o x q 4 + 2 o y q 1 + 2 o z q 2 2 o x q 4 + 2 o z q 2 2 o x q 3 4 o y q 2 + 2 o z q 1 2 o x q 2 + 2 o z q 4 2 o x q 1 4 o y q 4 + 2 o z q 3 2 o x q 3 2 o y q 2 2 o x q 4 2 o y q 1 4 o z q 2 2 o x q 1 + 2 o y q 4 4 o z q 3 2 o x q 2 + 2 o y q 3 . E43

Given the gyro measurement ω gyro b (relative to inertial frame), the angular velocity relative to orbit frame can be found as

ω o , gyro b = 0 ω gyro b R o b q ̂ k 1 R i o ω i , o i R 4 , E44

where the rotation matrix from orbit to body frame is constructed using the estimated quaternion and denoted by R o b q ̂ k 1 . The Madgwick filter can now be presented as

ω ̂ k b = 2 T q ̂ k 1 f f , E45
ω bias , k b = ω bias , k 1 b + ζ ω ̂ k b Δ T , E46
ω o , b b = H ω o , gyro b ω bias , k b , E47
q ̂ ̇ k = 1 2 T q ̂ k 1 0 ω o , b b β f f , E48
q ̂ k = q ̂ k 1 + q ̂ ̇ k Δ T , E49
q ̂ k = q ̂ k q ̂ k , E50

where β and ζ are gains, the time step is denoted by Δ T , the estimated angular velocity based on vector measurements is denoted ω ̂ k b R 4 , and the estimated gyro bias is denoted by ω bias , k b R 4 , while the angular velocity of the body frame relative to the orbit frame is denoted ω o , b b R 3 (expected output) and the estimated quaternion is denoted q ̂ k describing the body frame relative to the orbit frame. Note that the quaternion must be normalized to ensure unit length and that the first elements of ω ̂ k b , ω bias , k b R 4 are enforced to zero. To map the angular velocity from four to three elements, the projection matrix is defined as H = 0 I R 3 × 4 , which has a column vector of zeros followed by the identity matrix such that ω o , b b R 3 .

6.4. Simulation

Let a satellite have the inertia matrix as given in Eq. (43), which contains non-diagonal terms which therefore will create perturbing moments due to the gravity. Furthermore, let the satellite have the following initial conditions: q o , b 0 = 0.5 0.5 0.5 0.5 Τ and ω o , b b = 0.1 0.2 0.3 Τ with q ̂ o , b 0 = 1 0 0 0 Τ and ω ̂ o , b b = 0 0 0 Τ . The desired quaternion can be chosen as q o , d = 1 0 0 0 Τ , while ω o , d d = ω ̇ o , d d = 0 . To model noise in the sensor measurements, the quaternion is converted into Euler angles, where noise is added to the different sensors. Then, creating the rotation matrix from the noisy Euler angles allows the Sun vector, acceleration, and magnetometer models in the orbit frame to be rotated to the body frame, where the measurements now contain noise. The step size of the simulation is 0.01 , while the sensors are sampled every 0.1 s.

The quaternion and angular velocity error of the satellite are shown in Figure 18. After about 50 s, the objective of making the attitude error and angular velocity error go to zero is achieved. Since the attitude is not measured directly, the Madgwick filter is used for attitude estimation as shown in Figure 19. Both the quaternion error (estimated truth) and angular velocity error converge close to zero.

Figure 19.

Attitude and angular velocity during the maneuver [9].

From the PD+ controller, the desired torque is mapped to the desired thrust firings using bang-bang modulation (Figure 20). Figure 21 shows the thruster firings required to maintain the attitude error close to zero.

Figure 20.

Estimation error [9].

Figure 21.

Thruster firings to control the attitude [9].

Advertisement

7. Conclusion

This chapter has presented all the components required to create an attitude determination and control system for satellites in elliptical orbits. With this as basis, it is the hope by the author that the work can help in developing new results within attitude determination and control systems, ranging from nonlinear controllers to new understanding in orbital mechanics, attitude determination, new sensors, and new actuation methods and strategies.

References

  1. 1. Sidi MJ. Spacecraft Dynamics & Control. New York: Cambridge University Press; 1997
  2. 2. Wertz J, editor. Spacecraft Attitude Determination and Control. D. Dordrecht, Holland: Reidel Publishing Company; 1978
  3. 3. Vallado DA. Fundamentals of Astrodynamics and Applications. 3rd ed. El Segundo, California: Microcosm Press and Dordrecht, Boston, London: Kluwer Academic Publishers; 2007
  4. 4. Markley FL, Crassidis JL. Fundamentals of Spacecraft Attitude Determination and Control. El Segundo, California: Microcosm Press and New York, Heidelberg, Dordrecht London: Springer; 2014
  5. 5. Alarcon J, Örger N, Kim S, Soon L, Cho M. Aoba VELOX-IV attitude and orbit control system design for a LEO mission applicable to a future lunar mission. In: Proceedings of the 67th International Astronautical Congress; Guadalajara City, Mexico; 2016
  6. 6. Dechao R, Tao S, Lu C, Xiaoqian C, Yong Z. Attitude control system design and on-orbit performance analysis of nano-satellite - tian Tuo 1. Chinese Journal of Aeronautics. 2014;27(3):593-601
  7. 7. Nakajima Y, Murakami N, Ohtani T, Nakamura Y, Hirako K, Inoue K. SDS-4 attitude control system: In-flight results of three axis attitude control for small satellites. IFAC Proceedings Volumes. 2013;16(19):283-288
  8. 8. Fritz M, Shoer J, Singh L, Henderson T, McGee J, Rose R, Ruf C. Attitude determination and control system design for the CYGNSS microsatellite. In: Proceedings of the IEEE Aerospace Conference; Big Sky, Montana; 2015
  9. 9. Oland E. Attitude determination and control system for satellites in elliptical orbits—A complete solution. In: Proceedings of the 8th International Conference on Recent Advances in Space Technology (RAST); Istanbul, Turkey; 2017
  10. 10. Oland E, Houge T, Vedal F. Norwegian student satellite program—HiNCube. In: Proceedings of the 22nd Annual AIAA/USU Conference on Small Satellites; Utah, USA; 2008
  11. 11. Oland E, Schlanbusch R. Reaction wheel design for cubesats. In: Proceedings of the 4th International Conference on Recent Advances in Space Technologies (RAST); Istanbul, Turkey; 2009
  12. 12. Schlanbusch R, Oland E, Nicklasson PJ. Modeling and simulation of a cubesat using nonlinear control in an elliptic orbit. In: Proceedings of the 4th International Conference on Recent Advances in Space Technologies (RAST); Istanbul, Turkey; 2009
  13. 13. Madgwick S, Harrison A, Vaidyanathan R. Estimation of IMU and MARG orientation using a gradient descent algorithm. In: Proceedings of the 2011 IEEE International Conference on Rehabilitation Robotics; Zurich, Switzerland; 2011
  14. 14. Oland E. Autonomous inspection of the International Space Station. In: Proceedings of the 8th International Conference on Mechanical and Aerospace Engineering; Prague, Czech; 2017
  15. 15. Egeland O, Gravdahl JT. Modeling and Simulation for Automatic Control. Trondheim, Norway: Marine Cybernetics; 2002. ISBN: 82-92356-01-0
  16. 16. Schaub H, Junkins JL. Analytical Mechanics of Space Systems. AIAA American Institute of Aeronautics & Ast; 2003. pp. 1-19
  17. 17. Oland E, Andersen TS, Kristiansen R. Subsumption architecture applied to flight control using composite rotations. Automatica. 2016;69:195-200
  18. 18. Kristiansen R. Dynamic synchronization of spacecraft [PhD thesis]. Trondheim, Norway: Norwegian University of Science and Technology; 2008
  19. 19. Takegaki M, Arimoto S. A new feedback method for dynamic control of manipulators. ASME Journal of Dynamic Systems, Measurement, and Control. 1981;103(2):119-125
  20. 20. Paden B, Panja R. Globally asymptotically stable ‘PD+’ controller for robot manipulators. International Journal of Control. 1988;47(6):1697-1712
  21. 21. Kristiansen R, Nicklasson PJ, Gravdahl JT. Spacecraft coordination control in 6DOF: Integrator backstepping vs. passivity-based control. Automatica. 2008;44(11):2896-2901
  22. 22. Schlanbusch R, Loría A, Kristiansen R, Nicklasson PJ. PD+ based output feedback attitude control of rigid bodies. IEEE Transactions on Automatic Control. 2012;57(8):2146-2152
  23. 23. Oland E. A command-filtered backstepping approach to autonomous inspections using a quadrotor. In: Proceedings of the 24th Mediterranean Conference on Control and Automation; Athens, Greece; 2016
  24. 24. Hahn W. Stability of Motion. Berlin/Heidelberg/New York: Springer-Verlag; 1967. ISBN: 978-3-642-50087-9
  25. 25. Wiśniewski R. Satellite attitude control using only electromagnetic actuation [PhD thesis]. Aalborg University; 1996
  26. 26. Hu Q, Ma G. Flexible spacecraft vibration suppression using PWPF modulated input component command and sliding mode control. Asian Journal of Control. 2007;9(1):20-29
  27. 27. Psiaki M. Magnetic torquer attitude control via asymptotic periodic linear quadratic regulation. Journal of Guidance, Control, and Dynamics. 2001;24(2):386-394
  28. 28. Thébault E et al. International geomagnetic reference field: The 12th generation. Earth, Planets and Space. 2015;67(79):1-19
  29. 29. Shuster MD, Oh SD. Three-axis attitude determination from vector observations. Journal of Guidance and Control. 1981;4(1):70-77
  30. 30. Farrell JL. Attitude determination by kalman filtering. Automatica. 1970;6(3):419-430
  31. 31. Mahony R, Hamel T, Pflimlin J. Nonlinear complementary filters on the special orthogonal group. IEEE Transactions on Automatic Control. 2008;54(5):1203-1217

Notes

  • Figure created using the MATLAB script “international geomagnetic reference field (IGRF) model” by Drew Compston.
  • https://github.com/JDeeth/MagDec
  • https://github.com/scivision/pyigrf12

Written By

Espen Oland

Submitted: 01 March 2018 Reviewed: 20 July 2018 Published: 05 November 2018