Home Vision-Based CubeSat Closed-Loop Formation Control in Close Proximities
Article Open Access

Vision-Based CubeSat Closed-Loop Formation Control in Close Proximities

  • Farbod Fahimi EMAIL logo
Published/Copyright: April 8, 2019
Become an author with De Gruyter Brill

Abstract

A vision based formation and attitude controller has been derived and simulated for the formation keeping of two 3U CubeSats. Four markers are installed on the leader CubeSat. Two cameras are installed on the follower CubeSat. An efficient vision based pose estimation method is used to estimate the pose of the follower with respect to the leader. A Higher-Order Sliding Mode (HOSM) exact differentiator with finite-time convergence is derived to estimate the rate of the follower’s pose parameters. The follower’s pose and its time rate are fedback to HOSM formation and attitude controllers to correct any gradual drift in formation and pose of the follower. The simulations show the effectiveness of the approach, and its feasibility on existing hardware.

1 Introduction

Small satellites are lighter and less expensive to launch, and if one satellite fails it can be replaced with less cost. Yet, they can be used in constellations to perform important missions. For example, several projects at NASA can strongly benefit from the utilization of multiple satellites in orbit: Global Precipitation Measurement Constellation, Leonardo-BRDF, GPS Occultation Constellation, Magnetospheric Constellation, Global Ionosphere-Thermosphere-Mesosphere Constellation, etc. That is why many research institutions, including NASA’s Goddard Space Flight Center have been studying and designing and testing tools that enable the use of constellations of small satellites [1].

The architecture of the formation of small satellites have been studied by some researchers [2, 3]. A three-body problem modeling and an up to date model of the Dydimos binary asteroid has been used to highlighting benefits and limitations of stable and unstable formation flying orbits [4]. To design a realistic formation architecture, a multitude of operational scenarios such as desaturation, detumble, thruster firing, and target acquisition/recovery have been considered [5].

Another aspect of formation control of small satellites is the prescription and planning of the needed formation maneuvers at different situations. Planning of n-impulse fuel-optimal maneuvers for establishment and reconfiguration of spacecraft formations are considered for circular and elliptic orbits [6]. Collision avoidance maneuvers for a swarm of satellites in formation, which return to their original configuration after a threat has passed, is considered in [7] using biological rules of avoidance.

Other researchers focused on the control of separation distances and orientation of satellites in formations. The interaction between magnets and superconductors has been used as a mechanism to affect the relative pose of small satellites in a formation [8]. This mechanism, known as magnetic flux pinning, has been used with a Proportional-Integral-Derivative control law for choosing an optimal configuration for the spacecraft formation during a rest-to-rest reorientation maneuver [9]. Precision dual spacecraft formation flying has been proposed to enable a “virtual” telescope by utilizing the Constrained Model Predictive Control approach [10]. It was shown by simulations that the formation control using aerodynamic drag forces are feasible at altitudes between 500 km and 700 km [11]. The station-keeping, reconfiguration and collision avoidance of spacecraft in formation around eccentric reference orbits have been addressed by development of an LQR/APF control scheme [12]. The software that enables rendezvous, proximity operations, and docking for CubeSat formation flying has been designed in [13] using a dual-inertial state Extended Kalman Filter, and a fuel-optimal state-space impulsive guidance and control algorithm.

In this research, to address the GN&C needs of close formation flying of small satellites, a vision based pose estimation combined with robust Higher-Order Sliding Mode (HOSM) controllers is explored. First, a vision based pose estimation method is briefly introduced [14, 15]. Then, a HOSM exact differentiator with finite-time convergence is explained. Next, a HOSM formation controller and a HOSM attitude controller are presented. Finally, the vision system is integrated with the controllers and the performance of the whole system is shown via simulations.

2 System Architecture

The building blocks of the vision based control system and their relations are shown in Fig. 1. The blocks that are shown in solid lines are parts of the controller. The blocks shown in dashed lines represent the mathematical models of the actual hardware that are used for simulations. For the real implementation, these blocks will be replaced by the actual CubeSats and their sensors.

Fig. 1 The vision based formation control architecture
Fig. 1

The vision based formation control architecture

A user defines the “desired formation” (xd, yd, zd) and “desired attitude” (ϕd, θd, ψd) of the follower with respect to the leader according to the application at hand. Four recognizable markers j = 1, …, 4 are installed on the leader. Two cameras c1 and c2, installed on the follower, capture the images of the markers on the leader. The image pixel coordinates of the markers [(xpj, ypj)c1 and (xpj, ypj)c2] are derived by processing the camera images. These image pixel coordinates and the desired pose of the follower are fed to the “Mirage vision based pose estimation” algorithm, which provides the actual pose of the follower (x, y, z, ϕ, θ, ψ). The actual pose is differentiated by the “HOSM differentiator” in real time. The actual pose, its rate, and the desired pose are fed to the closed-loop “HOSM formation controller” and “HOSM attitude controller,” which determine the thruster forces (uf) and reaction wheel torques (τ) to correct any drift in formation and attitude of the follower. In the following, each building block is presented and discussed.

3 Desired Formation and Desired Attitude

The leader and follower CubeSats are shown in Fig. 2. There are two poses shown for the follower. One (on the left) is the desired position of the follower CubeSat with respect to the leader CubeSat. The desired pose of the follower is represented by a spatial frame {fd}, while the current pose of the leader is denoted by the frame {r}. Based on the application at hand, a user defines his/her desired relative formation (xd, yd, zd) and orientation (ϕd, θd, ψd) of the follower CubeSat with respect to the leader. Knowing the desired pose of the follower frame {fd} with respect to the leader frame {r}, one can define the known transformation matrix between the two frames Trfd.

Tfdr=Rz(ψd)Ry(θd)Rx(ϕd)xdydzd0001,Trfd=(Tfdr)1(1)

Here, Rz(.), Ry(.), and Rx(.) are the 3 × 3 rotation matrices about the z, y, and x axes, respectively.

4 Mirage Vision Based Pose Estimation

4.1 Pose estimation methodology

Figure 2 shows the leader and follower CubeSats. Two poses are shown for the follower. The one on the left is the desired (ideal) position of the follower CubeSat with respect to the leader CubeSat. However, the follower has drifted away from its desired pose with respect to the leader. The actual pose of the follower after the drift (shown on the right) is denoted by a spatial frame {f}.

Fig. 2 The leader and follower CubeSats with body frames
Fig. 2

The leader and follower CubeSats with body frames

Note that the transformation matrix Trfd is known from Eq. (1). If one can determine the transformation between the frames {f} and {fd} (i.e., the matrix Tfdf), then, the actual relative pose of the follower {f} with respect to the leader {r} can be determined by the following simple transformation.

Tfr=(TfdfTrfd)1(2)

The Mirage pose estimation method directly calculates the elements of matrix Tfdf via an analytical linear non-iterative solution, when two (or more) cameras are used.

The calculation of Tfdf involves the comparison of two images: the desired image and the actual image, which are defined in the following. Four non-planar markers (with known geometry) are installed on the leader (points 1 through 4 in Fig. 2). Two cameras are installed on the follower, but only one of them, represented by frame {ci}, is shown in Fig. 2. The camera {ci} (i = 1, 2) generates images of the markers. The image seen by the camera when the follower is at its desired pose is called the desired image. On the other hand, the image that the camera sees when the follower is in its actual pose is called the actual image.

The difference in the pixel coordinates of marker j (j = 1, …, 4) in the actual and desired images of camera ci (i = 1, 2) is a function of Tfdf. This difference in pixel coordinates is denoted by the following equation.

ejci=xpjxpjdypjypjdci(3)

where (xpj, ypj)ci and (xpjd,ypjd)ci are the pixel coordinates of marker j in camera i in the actual and desired image, respectively. Note that both the actual and the desired pixel coordinates are known. The actual pixel coordinates are found by extracting the pixel coordinates of the markers in the actual image via image processing. The desired pixel coordinates are found as follows.

After markers are physically installed on the leader, the Euclidean position vector of marker j with respect to the origin of {r} is denoted by (rr)j = [rx,ry,rz,1]jT. The desired 3D projection of marker j in the camera space (pcid)j=pcixdpciydpcizdjT is found by a series of transformation applied to the vector rr.

(pjd)ci=KciTfdciTrfd(rr)j(4)

Here, the 4 × 4 matrix Tfdci transforms any vector from frame {fd} to frame {ci}, and the 3 × 4 matrix Kci contains the intrinsic camera parameters (focal length, principle points and distortion parameters), which are available a priori via camera calibration. Then, the desired pixel coordinates are obtained.

xpjdypjdci=pjxd/pjzdpjyd/pjzdci(5)

Therefore, the pixel error ejci is known. If a relation between the pixel error ejci and the transformation matrix Tfdf is established, that relation can be used to solve for the elements of Tfdf. The derivation of such a relation is explained in the following.

First, the pixel error ejci can be calculated based on the coordinates in the 3D camera space.

ejci=xpjxpjdypjypjdci=pjxpjzpjxdpjzdpjypjzpjydpjzdci(6)

The actual 3D projection of marker j in the camera space {ci} is denoted.

(pj)ci=KciTfciTrf(rr)j(7)

Equation (7) is rewritten by incorporating the fact that Trf=TfdfTrfd.

(pj)ci=KciTfciTfdfTrfd(rr)j(8)

Note that there are no unknowns in Eq. (4) and the only unknowns in Eq. (8) are the twelve elements of the matrix Tfdf.

Tfdf=t1t4t7t10t2t5t8t11t3t6t9t120001(9)

Equation (9) is substituted in Eq. (8). The result of the substitution and Eq. (4) are expanded to obtain the components of (pj)ci and (pjd)ci. The resulting components are substituted in Eq. (6). After very involved manipulations, which can be found in [15], the following relation is found between the pixel error ejci and the elements of Tfdf.

ejci=Vjcitfdf+Yjci(10)

where Vci is a 2 × 12 matrix and Yci is a 2 × 1 vector with known values. For the detailed formulation of these parameters, see [15]. The 12 × 1 vector tfdf contains all 12 unknown elements of the transformation matrix Tfdf.

tfdf=[t1,t2,t3,t4,t5,t6,t7,t8,t9,t10,t11,t12]T(11)

Note that Eq. (10) includes 2 equations and 12 unknowns and cannot be solved in its current form. However, this equation is valid for camera ci (i = 1, 2) and marker j (j = 1, …, 4). For this case, Eq. (10) is written 8 times, covering the combinations of 2 cameras c1 and c2 and 4 markers.

e1c1e2c1e3c1e4c1e1c2e2c2e3c2e4c2=V1c1V2c1V3c1V4c1V1c2V2c2V3c2V4c2tfdf+Y1c1Y2c1Y3c1Y4c1Y1c2Y2c2Y3c2Y4c2,ore=Vtfdf+Y(12)

Equation (12) forms a linear system of 16 equations in terms of 12 unknown elements of tfdf, which can be easily solved in the Least-Square sense.

tfdf=(VTV)1(VT(eY))(13)

Now that the vector tfdf is calculated, the transformation matrix Tfdf is found. Then, Tfr is calculated using Eq. (2). The elements of Tfr are related to the pose parameters of the follower (q = [x, y, z]T and Φ = [ϕ, θ, ψ]T).

Tfr=Rz(ψ)Ry(θ)Rx(ϕ)xyz0001(14)

Therefore, knowing Tfr one can solve for q = [x, y, z]T and Φ = [ϕ, θ, ψ]T.

4.2 The simulated cameras

The block “simulated cameras” calculates the “actual pixel coordinates” of the marker j(j = 1, …, 4) for simulation only using the simulated pose of the follower CubeSat mathematical model. The actual 3D projection of marker j in the camera space is found using Eq. (7) and Trf=(Tfr)1. Finally, the simulated pixel coordinates are obtained as follows.

xpjypjci=pjx/pjzpjy/pjzci(15)

5 HOSM Differentiator

The pose vector Q = [q, Φ]T is not sufficient for feedback control. The rate of the pose vector is also required. The conventional differentiators provide asymptotic convergence. When the rate of a vector changes rapidly with time, the asymptotic convergence causes a phase lag, which is not good for robust control.

Here a Higher-Order Sliding Model (HOSM) differentiator is introduced that provides finite-time (as opposed to asymptotic) convergence to the exact derivative (in the absence of measurement noise). The HOSM differentiator is obtained as follows.

The time variable measured signal Q(t) is considered. It is desired to calculate (t) in real-time. A real-time estimate of the measured signal is defined as (t). At any given time the estimation error is defined.

yQ=Q~(t)Q(t)(16)

The derivative of the estimation error is given as follows.

y˙Q=Q~˙Q˙(17)

The rate of the estimated measurement Q~˙ is considered as a control input that affects the dynamics of the estimation error yQ.

v=Q~˙(18)

Therefore, the dynamics of the estimation error is obtained.

y˙Q=Q˙+v(19)

A control law for v is desired such that it can drive both yQ and Q to zero in finite-time. If both yQ and Q are driven to zero in finite-time, then, Q and Q~˙, at which point the exact derivative of Q is obtained. The following control law achieves the goal.

v=λ1 sign(Q~Q)T|Q~Q|12+q1(20)
q˙1=λ2 sign(Q~Q)(21)

Here, λ1 and λ2 are positive constants.

The differentiator is used as follows. The initial value of the measured signal Q(0) is known. The initial value of the estimated measured signal is set to (0) = Q(0). The control signals q1 and v are found by integrating Eq. (21) and calculating Eq. (20), respectively. The control signal v is applied to the dynamic system in Eq. (18), which is integrated to obtain . The obtained is fedback for control in Eqs. (20) and (21), and the process continues in time. In the meantime, the control signal v is the estimated derivative of the measured signal.

6 Formation Dynamic Model

6.1 Governing equations for simulations

The coordinate axes shown in Fig. 2 are considered. Let xrr and xfr denote the position of the leader and the follower satellites with respect to the geocentric system (X, Y, Z), but expressed along the moving axes (x, y, z) of frame {r} at the location of the leader satellite. Note that axes x, y, and z are radial, along track, and cross-track directions, respectively, defined by Hill and used in [2].

It is known that the effect of the follower’s thrusters force uf on the acceleration of the follower x¨fr is described by the follower’s equation of the motion.

mfx¨fr=FEfr+Frfr+Rfruf+Fdfr(22)

In this equation, mf is the mass of the follower satellite; FEfr is the pulling force from the Earth on the follower satellite; Frfr is the pulling force from the leader satellite on the follower satellite; and Fdfr is the resultant perturbing forces on the follower satellite. All vectors, except uf, have a superscript r, which indicates that they are written along the axes of the moving coordinate (x, y, z) of the frame {r}. The thrust vector uf is expressed in frame {f}, and Rfr transforms a vector from frame {f} to frame {r}.

This equation is integrated for simulations in the “formation dynamic model” block to provide xfr. The trajectory of the leader xrr is directly defined by the user.

6.2 Governing equations for control law derivation

Here, to achieve a precise formation, the relative position of the follower with respect to the leader will be controlled. Therefore, the dynamic equations of motion must be written as a relation between and the control forces from the follower’s thrusters uf.

The acceleration of the follower satellite can be written in terms of the acceleration of the leader satellite.

x¨fr=x¨rr+ω˙rr×q+ωrr×(ωrr×q)+2ωrr×q˙+q¨(23)

where q is the relative distance of the follower with respect to the leader along the moving axes (x, y, z) of frame {r}, and ωrr is the instantaneous rate of rotation of the leader around the Earth expressed along the axes of {r}. For the derivation of the controller, the “nominal” situation is used, in which the resultant perturbing forces on the follower satellite are neglected (Fdfr=0) and the nominal mass of the satellite is used (f).

Equation (22) is substituted in Eq. (23), and the result is solved for . The following is obtained

q¨=f^x+b^xuf(24)

where

f^x=(x¨rr+ω˙rr×q+ωrr×(ωrr×q)+2ωrr×q˙)+(F^Efr+F^rfr)/m^f(25)
b^x=(1/m^f)Rfr(26)

in which F^Efr and F^rfr are calculated using f.

Equation (24) describes the direct effect of the follower’s thrust uf on the relative motion of the follower with respect to the leader (q). This equation will be used for derivation of the formation controller.

6.3 Implementation notes

A controller that is derived based on Eq. (24) needs the measurement of the realtime acceleration of the leader (x¨rr), the relative position of the follower with respect to the leader (q), and its rate (). The acceleration x¨rr can be measured by an accelerometer on board of the leader satellite, and can be broadcast to the follower satellite. The relative position q is measured by the vision system, and its rate is observed by the HOSM differentiator.

7 Attitude Dynamic Model

7.1 Governing equations of motion

The ability to correct the satellite’s attitude is important, because after long periods of time, the external perturbing forces and moments will eventually rotate the satellite bodies. This may cause the loss of sight for vision-based formation correction maneuvers. Therefore, an attitude controller must be used to realign the satellites precisely when necessary.

A CubeSat body axes (xB, yB, zB) and its three orthogonal reaction wheels are shown in Fig. 3. The moment components τ = [τ1x, τ2y, τ3z]T are exerted by the motors of the reaction wheels on the CubeSat’s body. The following equations describes the rotational dynamics of the CubeSat body.

Fig. 3 A CubeSat with three orthogonal reaction wheels
Fig. 3

A CubeSat with three orthogonal reaction wheels

(IB+i=13BiIi)ω˙B=τωB×IBωBi=13Bi(ωB×Iiωi)+τD(27)
Φ˙=EωB(28)

The rotational dynamics of the reaction wheel are described by the following equation, in which θi(i = 1, 2, 3) is the angular position of reaction wheel i.

I1xxθ¨1I2yyθ¨2I3zzθ¨3=τi=13Ai(Iiω˙B+ωB×Iiωi)(29)

The derivation and the definition of the notation used in the above equations are found in the Appendix.

In summary, Eqs. (27), (28), and (29) are the complete dynamic model of the CubeSat and reaction wheels as a system, which are inserted in the “attitude dynamic model” block in Fig. 1. At any simulation step, the reaction wheel driving moments are known. One can calculate the CubeSat’s angular acceleration vector ω̇B using Eq. (27). Also, the reaction wheel driving moments and the CubeSat’s angular acceleration vector ω̇B just obtained from Eq. (27) can be used with Eq. (29) to calculate the reaction wheel’s angular acceleration (θ̈1, θ̈2, θ̈3). Integrating these angular accelerations will provide ωB and (θ̇1, θ̇2, θ̇3) for the next time step. The integration can go on by repeating the above steps.

7.2 Governing equations for control law derivations

Equation (27) is written in a more concise form.

ω˙B=f^ω+b^ωτ(30)

where

b^ω=(I^B+i=13BiI^i)1(31)
f^ω=b^ω(ωB×I^BωB+i=13Bi(ωB×I^iωi))(32)

are calculated using the “nominal” values of the system parameters. The following outputs are defined for the control system in Eq. (30).

y=ΦΦd(33)

where Φd is the desired orientation of the satellite, which in general can be a function of time. A controller must be derived that can stabilize the output y of the system in Eq. (30) and its time derivative at zero vector in finite time. The dynamics of the output y is derived for control design in the following.

The second time derivative of the surface variable is calculated.

y¨=Φ¨Φ¨d=Eω˙B+E˙ωBΦ¨d=E(f^ω+b^ωτ)+E˙ωBΦ¨d=(Ef^ω+E˙ωBΦ¨d)+(Eb^ω)τ

If the notations ϕ = Ef̂ω + ĖωBΦ̈d and ϕ = Eb̂ω are adopted, the model for attitude control derivation becomes.

y¨=f^ϕ+b^ϕτ(34)

The above equation is used for the derivation of a HOSM attitude controller.

8 HOSM Formation and Attitude Controllers

In this section a HOSM controller is derived for both the formation controller and the attitude controller. Note that the concise form of the dynamics of the two systems in Eq. (24) and Eq. (34) fit the following standard form.

σ¨=f^+b^u(35)

Here, a HOSM controller is derived based on the standard model in Eq. (35), which is interchangeable between systems in Eqs. (24) and (34) by using the correct σ, , , and u.

8.1 Nominal control

A change of state variables such as σ = z1 and σ̇ = z2 and change of the control signal such as ŵ = + b̂û are applied to the output system in Eq. (35). The following chain form is obtained.

z˙1=z2z˙2=w^(36)

It can be shown that the following feedback control law can stabilize the system in Eq. (36) at zero vector in finite time [16],

w^j=i=12kij sign(zij)|zij|vij,j=1,2,3(37)

where v1j = 3/5 and v2j = 3/4, and the control gains kij are found such that the following characteristic polynomial (p2 + k2jp + k1j = 0, j = 1, 2, 3) is Hurwitz. The above formulation is used as explained in the following. At each time step, the measurement of the real-time errors and their rates provide the feedback signals z1 and z2.

z1=σ(38)
z2=σ˙(39)

Then, the nominal control is calculated using Eq. (37). Finally the equivalent control is calculated by inverting the relation ŵ = + b̂û.

u^=b^1(f^+w^)(40)

The above “nominal” control works accurately if the system model has no uncertainty, that is if and are exact. However, normally, the real system is represented by {f} and {b}, which are different due to modeling and parameters uncertainties. In the following, the nominal control is amended to account for such uncertainties.

8.2 Extension to uncertain systems

The relation between the terms of the nominal system model and those of the actual system are defined as f = + and b = + , in which and are bounded. The following equation represents the real system.

σ¨=(f^+f~)+(b^+b~)u^(41)

Noting that z2 = σ̇ and substituting Eq. (40) in the above relation, one obtains.

z˙2=f~b~b^1f^+(I+b~b^1)w^(42)

To make sure that ż2 → 0 even in the presence of uncertainty, the nominal control ŵ in Eq. (42) is replaced by

w=w^Gsign(s)(43)
z˙aux=w^(44)

where s = z2 + zaux, and G is a positive constant. The gain G must be determined such that it is large enough to compensate for uncertain terms. This gain is determined using a Lyponuv design method.

8.3 Lyaponuv gain design

A Lyaponuv function is defined as V = 12sTs. The gain G must be determined such that = sT ≤ 0 for all s. Because = ż2 + żaux = ż2ŵ, is derived as follows.

V˙=sT[f~b~b^1f^]+sT(b~b^1)w^sTGsign(s)+sT(b~b^1)Gsign(s)(45)

To design the controller gain G, the following bounds are defined for the uncertain terms.

f~b~b^1f^ρb~b^1=b~b^11α(46)

Note that α ≈ 1. Knowing that cTd ≤ ∥c∥ ∥d∥ and ∥s∥ ≤ sTsign(s), and using Eq. (45), one can obtain the following.

V˙sρ+s(1α)w^Gs+G(1α)s(αGρ(1α)w^)s(47)

Equation (47) implies that, if the control gain G is selected to meet the following requirement,

Gρ+(1α)w^+ηα(48)

where η > 0, then, ≤ –ηs∥, or is negative for all s and V = 12sTs vanishes to zero despite bounded uncertainties in the system defined by Eq. (46), provided that the following control law is used.

u=b^1(f^+w^Gsign(s))(49)

Based on the formation dynamic model in Eq. (24), the above control law is used as the “HOSM formation controller” by setting = x, = x, z1 = q, z2 = , and u = uf. Also, based on the attitude dynamic model in Eq. (34), the above control law is used as the “HOSM attitude controller” by setting = ϕ, = ϕ, z1 = y, z2 = , and u = τ. The term ŵ is always calculated using the generic Eq. (37).

9 Simulation

A CubeSat similar to the one designed in [17] is considered. The moment of inertia of the satellite is ÎB ≈ diag(0.0067, 0.0333, 0.0333) kg.m2. The reactions wheels are SI’s 3-wheel orthogonal model [18], whose estimated mass moment of inertia are Î1 = diag(2.392, 1.247, 1.247) × 10–5 kg.m2, Î2 = diag(1.247, 2.392, 1.247) × 10–5 kg.m2, and Î3 = diag(1.247, 1.247, 2.392) × 10–5 kg.m2.

The effect of the resultant perturbing moment τD is neglected during the very short duration of the controller’s motion correction. An amount of 5% uncertainty has been assumed for the moments of inertia for the worst case. The total nominal mass of the follower is f = 5 kg, while the end of life mass after usage of all propellant of mf = 4.64 kg is used for simulation.

An in-track formation is assumed for the simulations. The desired roll, pitch, yaw of the follower with respect to the leader are all zeros (ϕd = θd = ψd = 0). However, a desired separation of yd = –5 m along the y direction of the follower is assumed, while xd = zd = 0 m.

When the formation/attitude correction is turned on, the follower has an orientation defined by ϕ(0) = 5, θ(0) = 5, and ψ(0) = –5. Also, x(0) = 0 m, y(0) = 5.5 m, and z(0) = 0 m.

The images of the leader’s markers in the follower’s cameras at the beginning of the simulation, when the follower is not at the desired formation, are shown in the left plot of Fig. 4. The actual image, calculated by the simulated cameras, is different from the desired image, calculated by the internals of the Mirage vision based pose estimation algorithm. This is because at the start of the simulation, the follower is not at the desired formation location.

Fig. 4 Left: The images of the markers in the cameras at the beginning of the simulation. Right: The images of the markers in the cameras at the end of the simulation.
Fig. 4

Left: The images of the markers in the cameras at the beginning of the simulation. Right: The images of the markers in the cameras at the end of the simulation.

The images of the leader’s markers in the follower’s cameras at the end of the simulation, when the follower reaches its desired formation, are shown in the right plot of Fig. 4. It can be seen that the actual image, calculated by the simulated cameras, coincides with the desired image, calculated by the internals of the Mirage vision based pose estimation algorithm. This is because at the end of the simulation, the follower is exactly at the desired formation location.

The relative position components of the follower with respect to the leader are shown in the left column of Fig. 5. The x and z components start and remain at their desired value of zero meters. The y component, which needed correction, goes from 5.5 m to the desired value of 5 m. The relative attitude components of the follower with respect to the leader are shown in the right column of Fig. 5. All components start with a 5° error in pose. They converge to their desired values of zero degrees.

Fig. 5 Relative pose components
Fig. 5

Relative pose components

The thrust components of the follower are shown in the left column of Fig. 6. The in-plane formation for this simulation encounters 0.5 meters of drift each month [2]. The total impulse for the 0.5 m correction is p = 0tfu2dt = 0.17 N.s, where tf is the time at which the formation error is less than 0.001 m. Assume that the CubeSat is using the hydrazine propulsion module presented in [19], which has a total life of 760 N.s of impulse. The thrusters can afford 4470 = (760/0.17) corrections, which, at the rate of one correction per month, lasts 372 years. The maximum needed thrust is less than 2.8 N, which is less than the maximum provided by the assumed hydrazine propulsion module [19]. The right column of Fig. 6 shows the torques of the follower’s reaction wheels. All moments are below the maximum capability of the SI’s orthogonal reaction wheels, which is 0.001 N.m [18].

Fig. 6 Follower’s thrust and reaction wheel torques
Fig. 6

Follower’s thrust and reaction wheel torques

10 Conclusions

A vision based HOSM formation and attitude controller was derived and simulated for the formation keeping of two 3U CubeSats. Vision-based pose estimation in junction with a HOSM differentiator provide accurate states in absence of GPS signals. The distance of the leader and follower satellites are directly controlled for precise formation keeping. For precise attitude control, the attitude controller was derived based on the a multibody dynamic model that included the dynamics of the reaction wheels. The simulations show the effectiveness of the approaches, and their feasibility in light of the practical maximum thrust and reaction wheel torques, and the length of satellite mission.

Acknowledgement

This research was performed at NASA-MSFC under the Faculty Fellowship Program in Summer 2016, for which I thank Dr. Frank Six, the program director, and Dr. John Rakoczy, my supervisor, for their strong support.

Appendix A: Derivations of the rotational dynamic model

A CubeSat body axes (xB, yB, zB) and its three orthogonal reaction wheels are shown in Fig. 3. The moment vectorsτ1, τ2, and τ3 are exerted by the reaction wheels on the CubeSat’s body. Note that these moment vectors include components that are the driving moments along the axes of the reaction wheels, as well as components that are internal (structural) moments perpendicular to the axes of the reaction wheels (Table1).

Table 1

Components of wheel moments

τ1τ2τ3
τ1x drivingτ2x internalτ3x internal
τ1y internalτ2y drivingτ3y internal
τ1z internalτ2z internalτ3z driving

The rotational equation of motion of the CubeSat body (excluding the reaction wheels) is written as follows.

IBω˙B+ωB×IBωB=τ1+τ2+τ3τD(50)

where IB is the centroidal mass moment of inertia of the CubeSat, excluding the reaction wheels, and ωB is the angular velocity of the CubeSat body. Both IB and ωB are expressed along the axes of the CubeSat’s body frame (xB, yB, zB), which implies that the vector moments τ1, τ2, and τ3 are also expressed in the body frame. τD is the unknown (but bounded) resultant of all the external perturbing moments.

The equation of motion of the reaction wheel i is

Iiω˙i+ωB×Iiωi=τi(i=1,2,3)(51)

where ω1 = ωB + [θ̇1, 0, 0]T, ω2 = ωB + [0, θ̇2, 0]T, and ω3 = ωB + [0, 0, θ̇3]T. Also, θi is the angle of rotation of the reaction wheel i about its shaft, and Ii is the diagonal mass moment of inertia tensor of the ith reaction wheel.

The twelve Eqs. (50) and (51) represent the dynamic state of the whole system, which include the six internal moments as listed in Table 1. The internal moments might be useful for the structural (or bearing) design of the reaction wheels, however, are not of interest for modeling the system for control design purposes. These six internal components of moment must be eliminated from twelve Eqs. (50) and (51). After the elimination, six (12 – 6 = 6) equations remain, which represent the dynamics of the vectors ωB and [θ̇1, θ̇2, θ̇3]T. The elimination procedure follows.

The following auxiliary matrices are defined to eliminate the internal moments in Eqs. (51).

A1=100000000,A2=000010000,A3=000000001(52)

Equation (29) is derived by simplifying the following summation: i=13Ai(Iiω˙i+ωB×Iiωi)=i=13Aiτi where τ = [τ1x, τ2y, τ3z]T, and Ii is diagonal.

The following auxiliary matrices are defined to eliminate the internal moments in Eq. (50).

B1=000010001,B2=100000001,B3=100010000(53)

Note that τ1 + τ2 + τ3 = τ + i=13Biτi, which can be shown by expanding components of τi (as shown in Table 1) on either side. Substituting for τ1 + τ2 + τ3 from Eq. (50) and substituting for τi from Eq. (51) and rearranging results in Eq. (27). Note that Ii is diagonal.

References

[1] Esper, J., Neeck, S., Slavin, J. A., Leitner, J., Wiscombe, W., and Bauer, F. H., 2003. “Nano/micro satellite constellations for Earth and space science”. Acta Astronautica, 52(9-12), pp. 785–791.10.1016/S0094-5765(03)00054-7Search in Google Scholar

[2] Sabol, C., Burns, R., and McLaughlin, C. A., 2001. “Satellite formation flying design and evolution”. Journal of Spacecraft and Rockets, 38(2), pp. 270–278.10.2514/2.3681Search in Google Scholar

[3] Carpenter, J. R., Leitner, J., Folta, D., and Burns, R., 2003. “Benchmark problems for spacecraft formation flying missions”. In AIAA Guidance, Navigation, and Control Conference and Exhibit. (AIAA 2003-5364).10.2514/6.2003-5364Search in Google Scholar

[4] Capannolo, A., Lavagna, M., Ferrari, F., and Lunghi, P., 2016. “Nanosatellite formation flying to enhance science in binary asteroid environment”. In Proceedings of the International Astronautical Congress, IAC. (IAC-16,B4,8,9,x35142).Search in Google Scholar

[5] Schulte, P. Z., and Spencer, D. A., 2016. “Development of an integrated spacecraft guidance, navigation, control subsystem for automated proximity operations”. Acta Astronautica, 118, pp. 168–186.10.1016/j.actaastro.2015.10.010Search in Google Scholar

[6] Roscoe, C. W., Westphal, J. J., Griesbach, J. D., and Schaub, H., 2015. “Formation establishment and reconfiguration using differential elements in J2-perturbed orbits”. Journal of Guidance, Control, and Dynamics, 38(9), pp. 1725–1740.10.1109/AERO.2014.6836272Search in Google Scholar

[7] Nag, S., and Summerer, L., 2013. “Behaviour based, autonomous and distributed scatter manoeuvres for satellite swarms”. Acta Astronautica, 82(1), pp. 95–109.10.1016/j.actaastro.2012.04.030Search in Google Scholar

[8] Wilson, W. R., Shoer, J. P., and Peck, M. A., 2009. “Demonstration of a magnetic locking flux-pinned revolute joint for use on cubesat-standard spacecraft”. In AIAA Guidance, Navigation, and Control Conference and Exhibit. (AIAA 2009-5904).10.2514/6.2009-5904Search in Google Scholar

[9] Sorgenfrei, M. C., Jones, L. L., Joshi, S. S., and Peck, M. A., 2013. “Testbed validation of location-scheduled control of a reconfigurable flux-pinned spacecraft formation”. Journal of Spacecraft and Rockets, 50(6), pp. 1235–1247.10.2514/1.A32463Search in Google Scholar

[10] Park, S.-Y., Calhoun, P. C., Shah, N., and Williams, T. W., 2014. “Orbit design and control of technology validation mission for refractive space telescope in formation flying”. In AIAA Guidance, Navigation, and Control Conference. (AIAA 2014-0451).10.2514/6.2014-0451Search in Google Scholar

[11] Omar, S. R., and Wersinger, J., 2015. “Satellite formation control using differential drag”. In 53rd AIAA Aerospace Sciences Meeting. (AIAA 2015-0002).10.2514/6.2015-0002Search in Google Scholar

[12] Palacios, L., Ceriotti, M., and Radice, G., 2013. “Autonomous distributed LQR/APF control algorithms for CubeSat swarms manoeuvring in eccentric orbits”. In Proceedings of the International Astronautical Congress, IAC, Vol. 7, pp. 5115–5121. (IAC-14-C1.5.7).Search in Google Scholar

[13] Roscoe, C. W., Westphal, J. J., Lutz, S., and Bennett, T., 2015. “Guidance, navigation, and control algorithms for cubesat formation flying”. In Advances in the Astronautical Sciences, Vol. 154, pp. 685–699. (AAS 15-113).Search in Google Scholar

[14] Dinc, S., Fahimi, F., and Aygun, R., 2016. “Vision-based trajectory tracking for mobile robots using Mirage pose estimation method”. IET Computer Vision, 10(5), August, pp. 450–458.10.1049/iet-cvi.2015.0153Search in Google Scholar

[15] Dinc, S., Fahimi, F., and Aygun, R., 2017. “Mirage: an o(n) time analytical solution to 3D camera pose estimation with multi-camera support”. Robotica, pp. 1–19. in press; Published online: 16 February 2017; https://doi.org/10.1017/S0263574716000874.Search in Google Scholar

[16] Defoort, M., Floquet, T., Kokosy, A., and Perruquetti, W., 2009. “A novel higher order sliding mode control scheme”. Systems and Control Letters, 58(2), pp. 102–108.10.1016/j.sysconle.2008.09.004Search in Google Scholar

[17] Zeledon, R., and Peck, M., 2013. “Attitude dynamics and control of a 3U CubeSat with electrolysis propulsion”. In AIAA Guidance, Navigation, and Control (GNC) Conference, AIAA. (AIAA 2013-4943).10.2514/6.2013-4943Search in Google Scholar

[18] Kjellberg, H. C., 2011. “Design of a CubeSat guidance, navigation, and control module”. Thesis for Master of Science in Engineering, The University of Texas at Austin, August. 10.13140/2.1.1469.7767.Search in Google Scholar

[19] Schmuland, D. T., Masse, R. K., and Sota, C. G., 2011. “Hydrazine propulsion module for CubeSats”. In Proceedings of the 25th Annual AIAA/USU Conference on Small Satellites, AIAA. (SSC11-X-4).Search in Google Scholar

Received: 2017-08-08
Accepted: 2018-02-21
Published Online: 2019-04-08
Published in Print: 2019-01-28

© 2019 Farbod Fahimi, published by De Gruyter

This work is licensed under the Creative Commons Attribution 4.0 Public License.

Articles in the same Issue

  1. Chebyshev Operational Matrix Method for Lane-Emden Problem
  2. Concentrating solar power tower technology: present status and outlook
  3. Control of separately excited DC motor with series multi-cells chopper using PI - Petri nets controller
  4. Effect of boundary roughness on nonlinear saturation of Rayleigh-Taylor instability in couple-stress fluid
  5. Effect of Heterogeneity on Imbibition Phenomena in Fluid Flow through Porous Media with Different Porous Materials
  6. Electro-osmotic flow of a third-grade fluid past a channel having stretching walls
  7. Heat transfer effect on MHD flow of a micropolar fluid through porous medium with uniform heat source and radiation
  8. Local convergence for an eighth order method for solving equations and systems of equations
  9. Numerical techniques for behavior of incompressible flow in steady two-dimensional motion due to a linearly stretching of porous sheet based on radial basis functions
  10. Influence of Non-linear Boussinesq Approximation on Natural Convective Flow of a Power-Law Fluid along an Inclined Plate under Convective Thermal Boundary Condition
  11. A reliable analytical approach for a fractional model of advection-dispersion equation
  12. Mass transfer around a slender drop in a nonlinear extensional flow
  13. Hydromagnetic Flow of Heat and Mass Transfer in a Nano Williamson Fluid Past a Vertical Plate With Thermal and Momentum Slip Effects: Numerical Study
  14. A Study on Convective-Radial Fins with Temperature-dependent Thermal Conductivity and Internal Heat Generation
  15. An effective technique for the conformable space-time fractional EW and modified EW equations
  16. Fractional variational iteration method for solving time-fractional Newell-Whitehead-Segel equation
  17. New exact and numerical solutions for the effect of suction or injection on flow of nanofluids past a stretching sheet
  18. Numerical investigation of MHD stagnation-point flow and heat transfer of sodium alginate non-Newtonian nanofluid
  19. A New Finance Chaotic System, its Electronic Circuit Realization, Passivity based Synchronization and an Application to Voice Encryption
  20. Analysis of Heat Transfer and Lifting Force in a Ferro-Nanofluid Based Porous Inclined Slider Bearing with Slip Conditions
  21. Application of QLM-Rational Legendre collocation method towards Eyring-Powell fluid model
  22. Hyperbolic rational solutions to a variety of conformable fractional Boussinesq-Like equations
  23. MHD nonaligned stagnation point flow of second grade fluid towards a porous rotating disk
  24. Nonlinear Dynamic Response of an Axially Functionally Graded (AFG) Beam Resting on Nonlinear Elastic Foundation Subjected to Moving Load
  25. Swirling flow of couple stress fluid due to a rotating disk
  26. MHD stagnation point slip flow due to a non-linearly moving surface with effect of non-uniform heat source
  27. Effect of aligned magnetic field on Casson fluid flow over a stretched surface of non-uniform thickness
  28. Nonhomogeneous porosity and thermal diffusivity effects on stability and instability of double-diffusive convection in a porous medium layer: Brinkman Model
  29. Magnetohydrodynamic(MHD) Boundary Layer Flow of Eyring-Powell Nanofluid Past Stretching Cylinder With Cattaneo-Christov Heat Flux Model
  30. On the connection coefficients and recurrence relations arising from expansions in series of modified generalized Laguerre polynomials: Applications on a semi-infinite domain
  31. An adaptive mesh method for time dependent singularly perturbed differential-difference equations
  32. On stretched magnetic flow of Carreau nanofluid with slip effects and nonlinear thermal radiation
  33. Rational exponential solutions of conformable space-time fractional equal-width equations
  34. Simultaneous impacts of Joule heating and variable heat source/sink on MHD 3D flow of Carreau-nanoliquids with temperature dependent viscosity
  35. Effect of magnetic field on imbibition phenomenon in fluid flow through fractured porous media with different porous material
  36. Impact of ohmic heating on MHD mixed convection flow of Casson fluid by considering Cross diffusion effect
  37. Mathematical Modelling Comparison of a Reciprocating, a Szorenyi Rotary, and a Wankel Rotary Engine
  38. Surface roughness effect on thermohydrodynamic analysis of journal bearings lubricated with couple stress fluids
  39. Convective conditions and dissipation on Tangent Hyperbolic fluid over a chemically heating exponentially porous sheet
  40. Unsteady Carreau-Casson fluids over a radiated shrinking sheet in a suspension of dust and graphene nanoparticles with non-Fourier heat flux
  41. An efficient numerical algorithm for solving system of Lane–Emden type equations arising in engineering
  42. New numerical method based on Generalized Bessel function to solve nonlinear Abel fractional differential equation of the first kind
  43. Numerical Study of Viscoelastic Micropolar Heat Transfer from a Vertical Cone for Thermal Polymer Coating
  44. Analysis of Bifurcation and Chaos of the Size-dependent Micro–plate Considering Damage
  45. Non-Similar Comutational Solutions for Double-Diffusive MHD Transport Phenomena for Non-Newtnian Nanofluid From a Horizontal Circular Cylinder
  46. Mathematical model on distributed denial of service attack through Internet of things in a network
  47. Postbuckling behavior of functionally graded CNT-reinforced nanocomposite plate with interphase effect
  48. Study of Weakly nonlinear Mass transport in Newtonian Fluid with Applied Magnetic Field under Concentration/Gravity modulation
  49. MHD slip flow of chemically reacting UCM fluid through a dilating channel with heat source/sink
  50. A Study on Non-Newtonian Transport Phenomena in Mhd Fluid Flow From a Vertical Cone With Navier Slip and Convective Heating
  51. Penetrative convection in a fluid saturated Darcy-Brinkman porous media with LTNE via internal heat source
  52. Traveling wave solutions for (3+1) dimensional conformable fractional Zakharov-Kuznetsov equation with power law nonlinearity
  53. Semitrailer Steering Control for Improved Articulated Vehicle Manoeuvrability and Stability
  54. Thermomechanical nonlinear stability of pressure-loaded CNT-reinforced composite doubly curved panels resting on elastic foundations
  55. Combination synchronization of fractional order n-chaotic systems using active backstepping design
  56. Vision-Based CubeSat Closed-Loop Formation Control in Close Proximities
  57. Effect of endoscope on the peristaltic transport of a couple stress fluid with heat transfer: Application to biomedicine
  58. Unsteady MHD Non-Newtonian Heat Transfer Nanofluids with Entropy Generation Analysis
  59. Mathematical Modelling of Hydromagnetic Casson non-Newtonian Nanofluid Convection Slip Flow from an Isothermal Sphere
  60. Influence of Joule Heating and Non-Linear Radiation on MHD 3D Dissipating Flow of Casson Nanofluid past a Non-Linear Stretching Sheet
  61. Radiative Flow of Third Grade Non-Newtonian Fluid From A Horizontal Circular Cylinder
  62. Application of Bessel functions and Jacobian free Newton method to solve time-fractional Burger equation
  63. A reliable algorithm for time-fractional Navier-Stokes equations via Laplace transform
  64. A multiple-step adaptive pseudospectral method for solving multi-order fractional differential equations
  65. A reliable numerical algorithm for a fractional model of Fitzhugh-Nagumo equation arising in the transmission of nerve impulses
  66. The expa function method and the conformable time-fractional KdV equations
  67. Comment on the paper: “Thermal radiation and chemical reaction effects on boundary layer slip flow and melting heat transfer of nanofluid induced by a nonlinear stretching sheet, M.R. Krishnamurthy, B.J. Gireesha, B.C. Prasannakumara, and Rama Subba Reddy Gorla, Nonlinear Engineering 2016, 5(3), 147-159”
  68. Three-Dimensional Boundary layer Flow and Heat Transfer of a Fluid Particle Suspension over a Stretching Sheet Embedded in a Porous Medium
  69. MHD three dimensional flow of Oldroyd-B nanofluid over a bidirectional stretching sheet: DTM-Padé Solution
  70. MHD Convection Fluid and Heat Transfer in an Inclined Micro-Porous-Channel
Downloaded on 10.9.2025 from https://www.degruyterbrill.com/document/doi/10.1515/nleng-2017-0147/html
Scroll to top button