Spacecraft Attitude Determination and Control System for an Earth Observation Satellite

Size: px
Start display at page:

Download "Spacecraft Attitude Determination and Control System for an Earth Observation Satellite"

Transcription

1 Spacecraft Attitude Determination and Control System for an Earth Observation Satellite Mario Rodriguez, Rafael Vazquez Escuela Técnica Superior de Ingeniería, University of Seville, Seville, Spain, Spacecraft optical payloads usually demand high levels of accuracy in order to track ground targets in relative motion, requiring pointing errors to remain in the arc-second range. The attitude control system has to achieve this level of performance while at the same time dealing with perturbation torques and imperfect attitude measurements. This paper addresses the complete analysis and design of a three-axis quaternion-based ADCS algorithm, from mission planning to real-time simulation using reaction wheels, gyroscopes, and direction measurements. A set of ground targets is considered; whenever any of the targets is at sight, the optical axis of the satellite shall maneuver to lock on the target and track it as the Earth rotates and the satellite moves on a certain sun-synchronous orbit. If no target is accessible, the satellite maneuvers to an attitude profile which maximizes solar array illumination. The proposed output-feedback control algorithm constructs a solution for the motion planning and then solves the tracking problem by combining the efficiency of the Finite Horizon Linear Quadratic Regulator (LQR) and the accuracy of the Multiplicative Extended Kalman Filter (MEKF). Realistic simulations including uncertainties and perturbations show the effectiveness of the algorithm. MATLAB -STK software integration provides a virtual visualization allowing intuitive evaluation and analysis of the problem. Nomenclature J a, J t Reaction wheels axial and transverse moment of inertia q Attitude Quaternion ω Body angular velocity ω w Reaction wheels angular velocities h Reaction wheels angular momentum n Orbital Velocity Control Torque u i I. Introduction Earth Observation satellites constitute a sizeable part of the present and projected satellite population. By observing the Earth from (typically low) orbit they are able to provide data for applications ranging from environmental monitoring to cartography. Current instrument capabilities are able to provide high levels of resolution provided that rather stringent pointing requirements are satisfied. Typically many targets need to be observed, resulting in a tighter schedule yielding shorter access windows and needing faster slewing maneuvers, raising the performance requirements and control power needs. Thus, there is a need for accurate Attitude Determination and Control Systems (ADCSs) that are able to deliver precise and fast tracking capabilities for targets on the ground. Many algorithms for ADCS exist in the literature. 1, 2 In this work, we explore a tracking algorithm composed of three parts. First, we develop a path planner that constructs attitude maneuvers to switch from one target to another. Subsequently, we use a finite-horizon LQR algorithm to make the maneuver asymptotically stable, at least for small deviations and perturbations. The particular ADCS architecture selected in this work for attitude control is a three axis momentum exchange control system, based on three reaction wheels placed on the principal axes of the spacecraft. Finally, we formulate an attitude estimator using integration of noisy inertial and vector measurements from a set of gyroscopes and a star tracker; our formulation is based on the Multiplicative Extended Kalman Filter. A quaternion approach is used in all three parts to obtain global attitude representation. We also provide some simulations where we explore how to tune the LQR parameters and investigate the robustness of the proposed design with respect to reaction wheel saturations. Additionally, the use of Matlab and STK integration has been applied to obtain visualizations of the different functions of the ADCS system in several scenarios. Aerospace Engineer, Aircraft and Spacecraft, mariorolu@gmail.com Associate Professor, Dpto. Ing. Aeroespacial, rvazquez1@us.es 1 of 11

2 We consider the following reconnaissance mission in this work. As a primary goal, the satellite shall track the city of Seville, every day at dawn. This city is the first of a target schedule, which also includes cities like Cape Town, Yakutat and Sydney. When none of the scheduled targets are visible, the satellite maneuvers to track a quasi-inertially-fixed attitude maximizing solar array output. Therefore, this attitude reference profile can be split into three attitude segments: target tracking, sun tracking and slewing maneuvers between those (see figure 1). The slewing maneuver is accomplished through a minimal energy rotation. The structure of this paper is as follows. We start with Section 2, where the attitude dynamic and kinematic models are described. Section 3 follows with the precise description of the tracking problem. Section 4 briefly describes the LQR controller. Section 5 introduces the key ideas behind the MEKF observer. Section 6 follows with the combined formulation of the LQR-MEKF algorithm, and finally, section 7 shows some simulation results. Appendix describes the interaction between Matlab and STK software used in this work. II. The model Since this mission yields a wide variety of attitude ranges and rates, a nonsingular attitude representation system must be adopted. Euler angles provide an intuitive attitude representation, but they imply trigonometric functions usage and not every attitude is well defined. Direction Cosine Matrix (DCM) is an useful tool for reference frame translations, but it is not an efficient figure when numerical integration is involved. The Euler angle-axis representation describes a rotation through the rotation axis e, and the angle rotated about it, θ. It is an intuitive attitude representation but not well defined when the rotation angle is zero. Amongst the wide variety of attitude representations available, the attitude quaternion is chosen in this work. It is an computationally efficient and non-singular attitude representation, along with the drawback of being a not very intuitive way of understanding the attitude of the satellite its mathematical form resembles a four-dimension complex number. The attitude quaternion encodes the Euler axis-angle representation as q = [ e sin θ/2 cos θ/2 ] T. Please note that it obeys the unit length constraint. The main advantage of this representation lies in how kinematic equations are written, as they only involve products q = 1 [ ] ω 2 q, (1) 0 where represents the quaternion product. 3 On the other hand, system dynamics are represented with the Euler equations d Γ dt = M = d Γ A dt + ω Γ, (2) B where A denotes the J2000 inertial reference frame, B is the body axes frame, and M is the perturbation torque. Given the altitude of the sun-synchronous orbit at hand, the most important applicable perturbation is Gravity Gradient (GG). In terms of the attitude quaternion, its components are 4 M 1 = 6n 2 (I 2 I 3 ) (q 1 q 4 + q 2 q 3 ) ( 1 2q1 2 2q2 2 ) M 2 = 6n 2 (I 3 I 1 ) (q 1 q 3 q 2 q 4 ) ( 1 2q1 2 2q2 2 ) (3) M 3 = 12n 2 (I 1 I 2 ) (q 1 q 3 q 2 q 4 ) (q 1 q 4 + q 2 q 3 ). The system angular momentum Γ in Euler equations (2) can be decomposed in the angular momentums of spacecraft and reaction wheels, as in Γ i = I i ω i + h i. Taking into account the motion equations of the reaction wheels 5 u i = J a ω i + ḣi and after some algebra, the model is represented with spacecraft dynamics equations (4), attitude kinematics equations (5) and reaction wheels motion dynamics (6). (I 1 J a ) ω 1 = (I 2 I 3 )ω 2 ω 3 h 3 ω 2 + h 2 ω 3 u 1 + M 1 (I 2 J a ) ω 2 = (I 3 I 1 )ω 3 ω 1 h 1 ω 3 + h 3 ω 1 u 2 + M 2 (4) (I 3 J a ) ω 3 = (I 1 I 2 )ω 1 ω 2 h 2 ω 1 + h 1 ω 2 u 3 + M 3 q 4 q 3 q 2 q 1 ω 1 q = 1 q 3 q 4 q 1 q 2 ω 2 2 q 2 q 1 q 4 q 3 ω 3 (5) q 1 q 2 q 3 q 4 0 (I 1 J a )ḣ1 = J a [(I 2 I 3 )ω 2 ω 3 h 3 ω 2 + h 2 ω 3 ] + I 1 u 1 (I 2 J a )ḣ2 = J a [(I 3 I 1 )ω 3 ω 1 h 1 ω 3 + h 3 ω 1 ] + I 2 u 2 (6) (I 3 J a )ḣ3 = J a [(I 1 I 2 )ω 1 ω 2 h 2 ω 1 + h 1 ω 2 ] + I 3 u 3 2 of 11

3 The resulting equations are a highly non-linear system x = f( x)+g( u), where x is the state vector and u is the control torque vector delivered by the actuators. The state x is a 10x1 vector which includes the angular velocity [ ] T vector, the attitude quaternion and the angular momentums of the reaction wheels, x = ω q h. III. The tracking problem In this work, a linear controller (LQR) is calculated and applied to the former non-linear system. To accomplish this, we must first linearize around a reference state which describes the ideal motion of the satellite to carry on the reconnaissance mission. The reference trajectory x ref is built according to the following key ideas: Solar array illumination: Most spacecraft solar arrays can rotate autonomously about their axis. In order to maximize illumination, the attitude quaternion shall be that whose Y body axis (the solar arrays axis) is perpendicular to the Sun vector, q ref (t) / Y body r (7) Ground target tracking: The optical axis of the spacecraft Z body shall point in the satellite-target direction, q ref (t) / Z body r sat-tar (8) Slew manoeuver: Rotation is performed by application of a certain rotation quaternion q rot (t) to the last quaternion of the former attitude profile q 1. This rotation quaternion is itself a rotation composition of q 1 and q 2, the first attitude quaternion of the next attitude profile, and an euler angle rate law. This law depends primarily on the available slewing time. q tr (t) = q rot (t) q 1 (9) Figure 1: Targets along its groundtrack. Black groundtrack portions indicate access to nearby target station Once the reference attitude quaternion is concatenated, the reference angular velocities ω ref and reaction wheels angular momentum h ref are derived. The reference state vector satisfies the non-linear system equations, xref = f( x ref ) + g( u ref ). If state errors are introduced in the formulation as δx = x x ref, δu = u uref, (10) a linear variable time (LVT) system can be derived by δx = f( x) x δx + g( u) ref u δu, (11) ref }{{}}{{} A(t) B(t) where A(t) and B(t) are the system matrices, and vary with time along with the reference trajectory. In equation (10), the error vector δx can be obtained by subtraction in its δω and δh components. However, the attitude quaternion error is obtained by a quaternion product. The state error is, then, δω = ω ω ref δx = x x ref δq = q q ref δh = h h ref 3 of 11

4 where the superscript denotes the quaternion conjugate. It is convenient to represent the attitude error in terms of the Gibbs vector a [ ] 1 a δq( a) =, (12) 4 + a 2 2 and will play an important rule in the MEKF estimator. IV. The Finite Horizon Linear Quadratic Regulator (LQR) Since the system from previous section δx = A δx + B δu is a linear time-variant system, the finite horizon LQR variant is employed. Table 1 summarizes the formulation. Variable time control feedback in equation (15) is fed with the optimal feedback gain K(t). This gain matrix is calculated by the Riccati equation (13). Differential Riccati equation: Ṡ = AT S + SA SBR 1 B T S + Q (13) t T, S(T ) given. Optimal feedback gain: Time-varying feedback: K(t) = R 1 B(t) T S(t) (14) δu = K(t) δx (15) Table 1: LQR summary Interestingly enough, the differential Riccati equation (13) must be solved backwards in time, from a given final condition S(T) in the finite horizon. This fact yields important implications in the algorithm architecture, as will be discussed later. This differential matrix equation is solved for the system matrices A(t) and B(t), and the weighting matrices Q(t), for the state error level desired; R(t), for the control input necessary; and S(t), for the final state error. In modern control design, weighting matrices are selected by the engineer. As an initial guess for this matrices, the Bryson s rule 6 is adopted. According to this rule, the diagonal elements of this matrices are inversely proportional to the maximum acceptable value of the square state error, control input and final error, respectively 1 Q ii = max [x i (t)] 2 i = 1, 2,..., 9 1 S ii = max [x i (T )] 2 i = 1, 2,..., 9 (16) 1 R jj = max [u j (t)] 2 j = 1, 2, 3. As will be shown later through simulation, the LQR has important guaranteed robustness properties. V. The Multiplicative Extended Kalman Filter (MEKF) So far, the formulation described is based on perfect knowledge of the state. Unfortunately, the ADCS system can only process information from a set of sensors, which are not perfectly accurate, nor provide measurements with infinite availability. The estimate of state error is then based upon a state estimation, δx(t) ˆ = ˆ x x ref. This sensor-fusion estimation is achieved in this work by the MEKF observer. The model considers inertial measurements of the satellite angular velocity ω from gyroscopes, which are considered to have an unlimited bandwidth, and vector measurements from a star tracker. The latter provides accurate attitude measurements in discrete time, every given refresh period. The discrete-continuous filtering is performed in three phases: propagation, update and reset. Propagation phase integrates inertial measurements provided by the gyroscopes from the last vector observation, through the kinematic equations (5). The Gaussian processes theory provides the matrix differential equation which allows the covariance matrix P propagation, P = F P + P F T + GQG T. (17) 4 of 11

5 Whenever a new vector measurement is available, the update phase estimates the attitude and angular velocity [ estimation errors, and accordingly corrects both the Kalman state vector x MEFK = a ] T b and the covariance matrix P. Finally, the reset phase updates the attitude quaternion estimate, and resets to zero the Kalman state vector. For the algorithm at hand, the sensors output is artificially generated. For the gyroscopes, the Farrenkopf s model is employed, 7 { ωgyr (t) = ω(t) + η 1 (t) + b (18) b(t) = η 2 (t), where η 1 (t) and η 2 (t) are white gaussian noises, tipically featured in most commercial gyroscopes. The MEKF will filter the noisy output signal of the gyroscope by estimation of the gyroscope error and measurement error. Since the attitude error estimate is written in terms of products (hence the name of the filter), it is parameterized in terms of the Gibbs vector in equation (12). This filter will obtain a statistically optimal estimate by minimization of the estimation error covariance matrix P, [ ] P (t) = E (x(t) ˆx(t)) (x(t) ˆx(t)) T (19) which shall be positive-semidefinite and symmetric. More information on the MEKF can be found in F. Landis Markley s work. 8 VI. Tracking with Imperfect Information Algorithm It consist in the application of the LQR controller together with the MEKF estimator. Figure (2) sketches the algorithm developed in this work. Once set the finite horizon time limits, the reference track during this time lapse yields an optimal gain matrix schedule through offline calculation of the Riccatti equation, backwards in time. This previously calculated and stored optimal gain K(t) feeds the online control loop, multiplied by the estimate of the state error. The resulting control input and the gravity gradient perturbations feed the satellite non-linear motion equations. The real state vector is artificially stained with sensor noises, so that realistic sensor outputs are filtered in the MEKF estimator, thus closing the online loop. Please note that the attitude error will be an addition of estimation error and control error. Figure 2: Tracking with Imperfect Information algorithm diagram Similarly to the MEKF algorithm, the online architecture of the problem is divided in three phases of propagation, measurement and reset. Propagation of the angular velocity is not necessary in this algorithm, since the real value of ω is obtained with eqs. (4). The gyro output is then calculated by Farrenkopf s model. Now, within the propagation phase, the real attitude quaternion q is obtained through integration of the non-linear model equations (4), (5) and (6), so that it can feed the GG equations (3) with real attitude information. The attitude quaternion estimate ˆq and the covariance matrix P are propagated until the next star tracker measurement is available. A Runge Kutta method is used in the propagation phase. The Dormand and Prince routine integrates the 50 resulting differential equations in each propagation phase. This fact, along with the complexity of random noise functions applied, makes the algorithm computationally expensive. Nonetheless, real implementation of the algorithm 5 of 11

6 would not need artificial generation of noise and propagation of the real attitude quaternion, then it is assumed to be computationally affordable. VII. Simulation Results In order to assess the ADCS performance, the attitude quaternion, control torques and pointing error will be evaluated. The pointing error, also known as Absolute Pointing Error (APE) according to ESA 9, is the Euler angle of the rotation quaternion between the reference attitude and the simulated attitude, i.e., APE(t) = 2 arccos δq 4 (t), (20) where δq 4 (t) is the scalar component of δq(t) = q ref (t) q sim (t). In addition to the APE, the ADCS performance can be appraised according to the energy index, which provides a measurement of the energy needed by the actuators. According to Junkins, 5 the energy index is and is measured in Joules. E = T 0 u(t) ω w (t) dx = N i=1 j=1 3 u ij ωij w dx [J], (21) The energy index can also be understood as the integral of the instantaneous power delivered to the reaction wheels P. The power P will be introduced for evaluation purposes as well. A. Tracking with Perfect Information Some simulation results are summarized here to analyze the LQR controller performance. In order to isolate the control problem, in this section we assume perfect knowledge of the state vector. As mentioned in section IV., the Finite Horizon LQR regulator can be tuned for higher accuracy or affordability, depending on the selected weighting matrices Q(t), R(t) and S(t). The ADCS performance will be analyzed for several tunings. For the sake of simplicity, we consider these weighting matrices constant in time and diagonal. The control parameters will be then their diagonal elements Q ii, R ii and S(T ) ii The selected simulation scenario is the following. From an initial attitude which yields a large APE off the initial reference attitude, the ADCS shall stabilize the Sun pointing attitude profile. Once the first target is at sight, it locks and tracks the target by maneuvering from the initial attitude reference profile. Figure 3: APE pointing error for R ii = 10 k, k = 1, 3, 5, 7, during initial stabilization maneuver (a) and Sun pointing attitude profile between two slewing maneuvers (b) Once the target is off sight, it maneuvers back to the sun pointing attitude profile. Sweeping the values of Q ii and R ii, the APE angular error as a function of time is presented in figures 3 and 4.a. As expected, the smaller R ii and/or higher Q ii is, the smaller the average APE results. Initial stabilization maneuver takes less time to yield acceptable values of APE, and slewing maneuvers are more accurate, allowing longer periods of ground target observation and Sun tracking. Please note that the second Sun pointing attitude profile does not necessarily lock the same attitude quaternion as the first Sun pointing attitude profile, since it is only necessary to suffice the condition in equation (7) 6 of 11

7 Figure 4: APE angular error (a) and angular velocity of one reaction wheel (b) during the initial stabilization phase, for several Q ii Figure 4.b shows that increasing values of Q ii lead to higher reaction wheels angular velocity, thus increasing the performance requirements of the ADCS system. Sweeping for several diagonal parameters of the final state error weighting matrix S(T ), figure 5 shows that it only affects the final instants of the simulation, while rendering no effect on the rest of the mission profile. Figure 5: APE angular error for increasing values of S(T ) qq, during the initial stabilization phase (a), a slewing maneuver (b) and final state surroundings (c). In a) and b), all the APE functions overlap. This fact could lead to neglect the S(T ) effect on the overall performance of the ADCS. Nonetheless, as mentioned in section IV., the architecture of the problem makes it necessary to store the previously calculated optimal gain K(t) in a memory buffer. Then, every certain amount of time, must be recalculated and then fed to the system. Then, small S(T ) ii parameters will generate bad initial conditions for the next control stage, thus reducing the ADCS performance periodically. However, this architecture can be seized if we consider different tuning parameters depending on the attitude profile. We would require higher precision in ground target tracking, holding cheap Sun tracking and slewing maneuvers. Figure 6 shows a real time simulation where high accuracy is tuned only for target tracking, while the rest of the simulation is tuned for control economy (blue). Figure 6: Realtime simulation for economic, accurate and mixed ADCS tunings This figure also shows a full-time affordably tuned ADCS (red), and a full-time accurate ADCS (green). Simulation results show that the mixed controller saves up to a 26% control energy, holding the same accuracy as the precise ADCS during the earth observation mission profile. 7 of 11

8 B. Limited Control Torque As previously mentioned, a tight target schedule can lead to fast slewing maneuvers, raising the control power needs. Unfortunately, reaction wheels motors cannot deliver unlimited torque, as this parameter compromises the reaction wheel dimensions, weight and power consumption. Thus, a very demanding attitude reference profile along with a too accurately tuned LQR can lead to control torques too high to be delivered by the actuators. In this section, we simulate this situation. The control torque is artificially truncated under the maximum necessary level. Figure 7: Simulation under limited torque conditions, with overshooting up to t 7000s Figure 7 shows the attitude quaternion and the APE during a slewing maneuver to a ground tracking attitude profile with limited control output. The slewing maneuver commanded by the reference profile (from 6700 to approximately 6800 s) is too demanding for the reaction wheel motors. Then, wide overshooting takes place, with a maximum APE about 40 degrees. In spite of the violation of the small errors hypothesis based upon which the tracking linearization is formulated, the LQR robustness allows the attitude quaternion to track the reference after 300 seconds of overshooting. Once the control input needs are smaller than the reaction wheels motors output torque, the controller tracks the reference as if it did not overshoot in the first place. This fact highlights the need to model an attitude reference for the slewing maneuvers, since steep changes in the reference could lead to this kind of scenario. C. MEKF In this section we briefly assess the MEKF algorithm implemented. In order to evaluate the estimation error, the Attitude Measurement Error (AME) is similarly defined as its control counterpart, AME(t) = 2 arccos δq 4 (t), (22) where δq 4 (t) is the scalar component of δq(t) = q ref (t) q est (t). We analyze the AME versus several values of the gyroscope error variances η 1 and η 2, ranging values found in real spacecraft grade inertial units. Figure 8 shows the mean AME along the simulation period as a function of (η 1, η 2 ). AME MEKF rapidly increases with η 1, while it remains almost constant with η 2. But most importantly is shown a huge increase in AME MEKF for small values of η 1 and large values of η 2. It is found that this region of the (η 1, η 2 ) plane yields bigger roundoff errors within the Runge Kutta integration method, thus making the covariance matrix P lose its assumed symmetry. This fact dramatically decreases the LAPACK number of the inverse matrix involved in the Kalman gain calculation, leading to the MEKF instability. In this work, it is proposed to force the covariance matrix symmetry in equation (17), by P = F P + P F T + GQG T = F P + P T F T + Q = F P + (F P ) T + Q. (23) in which the PLATO exoplanetary system explorer inertial unit lies within, see figure 8.b 8 of 11

9 Figure 8: AME MEKF (η 1, η 2 ), instability (a); projection over (η 1, η 2 ) plane (b) This symmetrization solution removes the MEKF instability with very little additional computational cost. D. Tracking with Imperfect Information Simulation results are shown here to demonstrate the complete ADCS algorithm detailed in section VI. In order to understand this simulation, several angular errors must be defined: Absolute measurement error AME Euler angle of the rotation quaternion between the attitude estimate and the actual attitude. It is represented as the light blue line. Fictitious angular error Euler angle of the rotation quaternion between the attitude estimate and the reference attitude quaternion. It determines how much control input needs to be delivered to the actuators. It is represented as the red line. Angular update error Euler angle of the rotation quaternion between the attitude estimate before and after the star tarcker measurement update. It is represented as the green line. Absolute pointing error APE Now, the APE measures the angular error between the actual attitude quaternion and the reference attitud quaternion. Thus, it is the ultimate performance figure for the ADCS. Represented as the blue line, it is can be considered as the qualitative addition of the fictitious angular error and the absolute measurement error. Figure 9: Relevant angular errors in the tracking with imperfect information problem, during a sun tracking attitude profile Figure 9 shows a Sun pointing attitude profile. The AME increases with time up to the next star tracker 9 of 11

10 measurement update, delivered every 5 seconds, when it suddenly decreases. The APE evolves in a similar way, according to the accuracy-tuned LQR. Each star tracker update yields a sudden increase in the fictitious error, due to the steep change of the attitude estimate. Since the reference attitude is (almost) constant for this attitude profile, the fictitious error increase can be understood as sudden increments of the absolute value of the control input. As a result, slight delays of the actual attitude with respect to the attitude estimate take place. Figure 10 shows the same simulation, during a ground tracking attitude profile (a), compared to the perfect information algorithm in the same situation (b). It clearly depicts the high frequency noise induced by the estimation technique. This perturbation is known as Relative Pointing Error (RPE) 9, also known in the field as jitter. This disturbance may have an important impact on the spacecraft optic systems, and its mitigation is left as future work. In spite of the RPE perturbation, this simulation features the noise characteristics of the HRG gyroscopes of the Figure 10: Relevant angular errors in the tracking with imperfect information problem, during a ground target tracking attitude profile SSIRU inertial unit, onboard Herschel Space Telescope, and the Cryosat TERMA HE5AS star tracker. Simulation results show an achieved average pointing error of 0.7 arc-seconds. VIII. Conclusion Advanced techniques for attitude control and estimation theories are implemented. The proposed algorithm provides an heuristic yet precise platform of analysis and dimensioning of a three axis estimation and control system. Fully customizable from orbital parameters to ground-station targets scheduling, provides accurate information on sensors and actuator performances required for a certain mission. For a given assembly of satellite and sensors/actuators, it yields quantitative and qualitative information on how it could perform on a certain observation mission, and give hints on the optical system performance required. The robustness of the algorithm is demonstrated under some adverse situations. As future work, implementation of a jitter reduction system can be considered. Also, the overall performance of the control system could be greatly improved with the implementation of energy/momentum wheels. 10 The wheel cluster configuration accomplishes both attitude actuation and kinetic energy storage, thus rendering the traditional chemical batteries unnecessary. Appendix: MATLAB -STK software integration As it has been pointed out above, the attitude quaternion is an efficient mean for attitude representation, but it makes difficult to understand the geometry underlying the formulation. Geometric understanding of the problem is utterly important by means of validation, mission planning and software debugging. This drawback is avoided with three dimensional motion representation in the MATLAB -STK simulation platform developed. The operation of the developed algorithm is sketched in figure CreaEscenario.m Sets the TCP/IP link between MATLAB and STK. Generates the STK scenario simulation parameters, and creates several auxiliary objects necessary for the simulation. 2. Orbita.m Calculates the desired orbit. The resulting keplerian elements are fed to the STK propagator J2Perturbation. This propagator takes into account the westward nodal regression typical of sun-synchronous orbits. It returns the calculated keplerian elements and the epoch. 3. Referencia.m With the keplerian elements calculated by Orbita.m, the target schedule and the slewing maneuver time, this script, calculates the reference state vector as explained above. It also animates the reference satellite representation in STK. 10 of 11

11 Figure 11: Flux diagram of the MATLAB-STK attitude simulation platform 4. Riccati.m With the reference state vector calculated by Referencia.m and the spacecraft mass parameters, it solves the differential Riccati equation (13), and returns the optimal gain matrix K(t). This script does not interact with STK. 5. E C Actitud.m This script is fed with the optimal gain matrix K(t) calculated by Riccati.m, the characteristic error variances of the sensors (gyros and star tracker), and the refresh rate of the star tracker. This routine solves the final tracking problem with imperfect information, by implementation of propagation/integration, update and reset phases. Along with several Matlab representations, this code sends both real (simulated) and estimated attitude quaternions for their representation in STK, q sim (t) and q est (t). References 1 Sidi, M. J., Spacecraft Dynamics and Control: A Practical Engineering Approach, Vol. 7 of Cambridge Aerospace Series, Cambridge University Press, New York, NY., A. H. de Ruiter, Christopher Damaren, J. R. F., Spacecraft Dynamics and Control: An Introduction, Wiley, Lefferts, E. J., Markley, F. L., and Shuster, M. D., Kalman Filtering for Spacecraft Attitude Estimation, Journal of Guidance, Control, and Dynamics, Vol. 5, No. 5, 1982, pp Wie, B., Space Vehicle Dynamics and Control,, Inc., Junkins, J. L., J. D. Turner, J., and Ho, Y.-C., Optimal Spacecraft Rotational Maneuvers, Elsevier, New York, Bryson, A. E., Control of Spacecraft and Aircraft, Princeton University Press, Princeton, NJ., Farrenkopf, R. L., Analytic Steady-State Accuracy Solutions for Two Common Spacecraft Attitude Estimators, Journal of Guidance and Control, Vol. 1, No. 4, 1978, pp Markley, F. L., Attitude Error Representations for Kalman Filtering, Journal of Guidance, Control, and Dynamics, Vol. 26, No. 2, 2003, pp ESA, Herschel/Planck System Requirements Specifications, SCI-PT-RS-05991, Vol. 3, No. 3, Tsiotras, P., Shen, H., and Hall, C., Satellite Attitude Control and Power Tracking with Energy/Momentum Wheels, Journal of Guidance, Control, and Dynamics, Vol. 24, No. 1, 2001, pp of 11

FIBER OPTIC GYRO-BASED ATTITUDE DETERMINATION FOR HIGH- PERFORMANCE TARGET TRACKING

FIBER OPTIC GYRO-BASED ATTITUDE DETERMINATION FOR HIGH- PERFORMANCE TARGET TRACKING FIBER OPTIC GYRO-BASED ATTITUDE DETERMINATION FOR HIGH- PERFORMANCE TARGET TRACKING Elias F. Solorzano University of Toronto (Space Flight Laboratory) Toronto, ON (Canada) August 10 th, 2016 30 th AIAA/USU

More information

Mixed Control Moment Gyro and Momentum Wheel Attitude Control Strategies

Mixed Control Moment Gyro and Momentum Wheel Attitude Control Strategies AAS03-558 Mixed Control Moment Gyro and Momentum Wheel Attitude Control Strategies C. Eugene Skelton II and Christopher D. Hall Department of Aerospace & Ocean Engineering Virginia Polytechnic Institute

More information

Tracking Rigid Body Motion Using Thrusters and Momentum. Wheels

Tracking Rigid Body Motion Using Thrusters and Momentum. Wheels JAS 199 Tracking Rigid Body Motion Using Thrusters and Momentum Wheels Christopher D. Hall, Panagiotis Tsiotras, and Haijun Shen Abstract Tracking control laws are developed for a rigid spacecraft using

More information

Visual Feedback Attitude Control of a Bias Momentum Micro Satellite using Two Wheels

Visual Feedback Attitude Control of a Bias Momentum Micro Satellite using Two Wheels Visual Feedback Attitude Control of a Bias Momentum Micro Satellite using Two Wheels Fuyuto Terui a, Nobutada Sako b, Keisuke Yoshihara c, Toru Yamamoto c, Shinichi Nakasuka b a National Aerospace Laboratory

More information

Linear Feedback Control Using Quasi Velocities

Linear Feedback Control Using Quasi Velocities Linear Feedback Control Using Quasi Velocities Andrew J Sinclair Auburn University, Auburn, Alabama 36849 John E Hurtado and John L Junkins Texas A&M University, College Station, Texas 77843 A novel approach

More information

Attitude Determination for NPS Three-Axis Spacecraft Simulator

Attitude Determination for NPS Three-Axis Spacecraft Simulator AIAA/AAS Astrodynamics Specialist Conference and Exhibit 6-9 August 4, Providence, Rhode Island AIAA 4-5386 Attitude Determination for NPS Three-Axis Spacecraft Simulator Jong-Woo Kim, Roberto Cristi and

More information

Extension of Farrenkopf Steady-State Solutions with Estimated Angular Rate

Extension of Farrenkopf Steady-State Solutions with Estimated Angular Rate Extension of Farrenopf Steady-State Solutions with Estimated Angular Rate Andrew D. Dianetti and John L. Crassidis University at Buffalo, State University of New Yor, Amherst, NY 46-44 Steady-state solutions

More information

9 th AAS/AIAA Astrodynamics Specialist Conference Breckenridge, CO February 7 10, 1999

9 th AAS/AIAA Astrodynamics Specialist Conference Breckenridge, CO February 7 10, 1999 AAS 99-139 American Institute of Aeronautics and Astronautics MATLAB TOOLBOX FOR RIGID BODY KINEMATICS Hanspeter Schaub and John L. Junkins 9 th AAS/AIAA Astrodynamics Specialist Conference Breckenridge,

More information

Multiplicative vs. Additive Filtering for Spacecraft Attitude Determination

Multiplicative vs. Additive Filtering for Spacecraft Attitude Determination Multiplicative vs. Additive Filtering for Spacecraft Attitude Determination F. Landis Markley, NASA s Goddard Space Flight Center, Greenbelt, MD, USA Abstract The absence of a globally nonsingular three-parameter

More information

MAE 142 Homework #5 Due Friday, March 13, 2009

MAE 142 Homework #5 Due Friday, March 13, 2009 MAE 142 Homework #5 Due Friday, March 13, 2009 Please read through the entire homework set before beginning. Also, please label clearly your answers and summarize your findings as concisely as possible.

More information

WEIGHTING MATRICES DETERMINATION USING POLE PLACEMENT FOR TRACKING MANEUVERS

WEIGHTING MATRICES DETERMINATION USING POLE PLACEMENT FOR TRACKING MANEUVERS U.P.B. Sci. Bull., Series D, Vol. 75, Iss. 2, 2013 ISSN 1454-2358 WEIGHTING MATRICES DETERMINATION USING POLE PLACEMENT FOR TRACKING MANEUVERS Raluca M. STEFANESCU 1, Claudiu L. PRIOROC 2, Adrian M. STOICA

More information

Attitude Regulation About a Fixed Rotation Axis

Attitude Regulation About a Fixed Rotation Axis AIAA Journal of Guidance, Control, & Dynamics Revised Submission, December, 22 Attitude Regulation About a Fixed Rotation Axis Jonathan Lawton Raytheon Systems Inc. Tucson, Arizona 85734 Randal W. Beard

More information

Quaternion-Based Tracking Control Law Design For Tracking Mode

Quaternion-Based Tracking Control Law Design For Tracking Mode A. M. Elbeltagy Egyptian Armed forces Conference on small satellites. 2016 Logan, Utah, USA Paper objectives Introduction Presentation Agenda Spacecraft combined nonlinear model Proposed RW nonlinear attitude

More information

Adaptive Unscented Kalman Filter with Multiple Fading Factors for Pico Satellite Attitude Estimation

Adaptive Unscented Kalman Filter with Multiple Fading Factors for Pico Satellite Attitude Estimation Adaptive Unscented Kalman Filter with Multiple Fading Factors for Pico Satellite Attitude Estimation Halil Ersin Söken and Chingiz Hajiyev Aeronautics and Astronautics Faculty Istanbul Technical University

More information

SATELLITE ATTITUDE CONTROL SYSTEM DESIGN WITH NONLINEAR DYNAMICS AND KINEMTICS OF QUATERNION USING REACTION WHEELS

SATELLITE ATTITUDE CONTROL SYSTEM DESIGN WITH NONLINEAR DYNAMICS AND KINEMTICS OF QUATERNION USING REACTION WHEELS SATELLITE ATTITUDE CONTROL SYSTEM DESIGN WITH NONLINEAR DYNAMICS AND KINEMTICS OF QUATERNION USING REACTION WHEELS Breno Braga Galvao Maria Cristina Mendes Faustino Luiz Carlos Gadelha de Souza breno.braga.galvao@gmail.com

More information

Design Architecture of Attitude Determination and Control System of ICUBE

Design Architecture of Attitude Determination and Control System of ICUBE Design Architecture of Attitude Determination and Control System of ICUBE 9th Annual Spring CubeSat Developers' Workshop, USA Author : Co-Author: Affiliation: Naqvi Najam Abbas Dr. Li YanJun Space Academy,

More information

Space Surveillance with Star Trackers. Part II: Orbit Estimation

Space Surveillance with Star Trackers. Part II: Orbit Estimation AAS -3 Space Surveillance with Star Trackers. Part II: Orbit Estimation Ossama Abdelkhalik, Daniele Mortari, and John L. Junkins Texas A&M University, College Station, Texas 7783-3 Abstract The problem

More information

A Miniaturized Satellite Attitude Determination and Control System with Autonomous Calibration Capabilities

A Miniaturized Satellite Attitude Determination and Control System with Autonomous Calibration Capabilities A Miniaturized Satellite Attitude Determination and Control System with Autonomous Calibration Capabilities Sanny Omar Dr. David Beale Dr. JM Wersinger Introduction ADACS designed for CubeSats CubeSats

More information

AN ANALYTICAL SOLUTION TO QUICK-RESPONSE COLLISION AVOIDANCE MANEUVERS IN LOW EARTH ORBIT

AN ANALYTICAL SOLUTION TO QUICK-RESPONSE COLLISION AVOIDANCE MANEUVERS IN LOW EARTH ORBIT AAS 16-366 AN ANALYTICAL SOLUTION TO QUICK-RESPONSE COLLISION AVOIDANCE MANEUVERS IN LOW EARTH ORBIT Jason A. Reiter * and David B. Spencer INTRODUCTION Collision avoidance maneuvers to prevent orbital

More information

IAA-CU A Simulator for Robust Attitude Control of Cubesat Deploying Satellites

IAA-CU A Simulator for Robust Attitude Control of Cubesat Deploying Satellites A Simulator for Robust Attitude Control of Cubesat Deploying Satellites Giovanni Mattei, George Georgiou, Angelo Pignatelli, Salvatore Monaco Abstract The paper deals with the development and testing of

More information

PRELIMINARY HARDWARE DESIGN OF ATTITUDE CONTROL SUBSYSTEM OF LEONIDAS SPACECRAFT

PRELIMINARY HARDWARE DESIGN OF ATTITUDE CONTROL SUBSYSTEM OF LEONIDAS SPACECRAFT PRELIMINARY HARDWARE DESIGN OF ATTITUDE CONTROL SUBSYSTEM OF LEONIDAS SPACECRAFT Chak Shing Jackie Chan College of Engineering University of Hawai i at Mānoa Honolulu, HI 96822 ABSTRACT In order to monitor

More information

Angular Velocity Determination Directly from Star Tracker Measurements

Angular Velocity Determination Directly from Star Tracker Measurements Angular Velocity Determination Directly from Star Tracker Measurements John L. Crassidis Introduction Star trackers are increasingly used on modern day spacecraft. With the rapid advancement of imaging

More information

Spacecraft Angular Rate Estimation Algorithms For Star Tracker-Based Attitude Determination

Spacecraft Angular Rate Estimation Algorithms For Star Tracker-Based Attitude Determination AAS 3-191 Spacecraft Angular Rate Estimation Algorithms For Star Tracker-Based Attitude Determination Puneet Singla John L. Crassidis and John L. Junkins Texas A&M University, College Station, TX 77843

More information

Spacecraft Attitude and Power Control Using Variable Speed Control Moment Gyros. Hyungjoo Yoon

Spacecraft Attitude and Power Control Using Variable Speed Control Moment Gyros. Hyungjoo Yoon Spacecraft Attitude and Power Control Using Variable Speed Control Moment Gyros A Thesis Presented to The Academic Faculty by Hyungjoo Yoon In Partial Fulfillment of the Requirements for the Degree Doctor

More information

*School of Aeronautics and Astronautics, Purdue University, West Lafayette, IN

*School of Aeronautics and Astronautics, Purdue University, West Lafayette, IN NEW CONTROL LAWS FOR THE ATTITUDE STABILIZATION OF RIGID BODIES PANAGIOTIS TSIOTRAS *School of Aeronautics and Astronautics, Purdue University, West Lafayette, IN 7907. Abstract. This paper introduces

More information

NEW EUMETSAT POLAR SYSTEM ATTITUDE MONITORING SOFTWARE

NEW EUMETSAT POLAR SYSTEM ATTITUDE MONITORING SOFTWARE NEW EUMETSAT POLAR SYSTEM ATTITUDE MONITORING SOFTWARE Pablo García Sánchez (1), Antonio Pérez Cambriles (2), Jorge Eufrásio (3), Pier Luigi Righetti (4) (1) GMV Aerospace and Defence, S.A.U., Email: pgarcia@gmv.com,

More information

Spacecraft Bus / Platform

Spacecraft Bus / Platform Spacecraft Bus / Platform Propulsion Thrusters ADCS: Attitude Determination and Control Subsystem Shield CDH: Command and Data Handling Subsystem Payload Communication Thermal Power Structure and Mechanisms

More information

An Inverse Dynamics Attitude Control System with Autonomous Calibration. Sanny Omar Dr. David Beale Dr. JM Wersinger

An Inverse Dynamics Attitude Control System with Autonomous Calibration. Sanny Omar Dr. David Beale Dr. JM Wersinger An Inverse Dynamics Attitude Control System with Autonomous Calibration Sanny Omar Dr. David Beale Dr. JM Wersinger Outline Attitude Determination and Control Systems (ADACS) Overview Coordinate Frames

More information

IAC-11-C1.5.9 INERTIA-FREE ATTITUDE CONTROL OF SPACECRAFT WITH UNKNOWN TIME-VARYING MASS DISTRIBUTION

IAC-11-C1.5.9 INERTIA-FREE ATTITUDE CONTROL OF SPACECRAFT WITH UNKNOWN TIME-VARYING MASS DISTRIBUTION 6nd International Astronautical Congress, Cape Town, SA. Copyright by the International Astronautical Federation. All rights reserved IAC--C.5.9 INERTIA-FREE ATTITUDE CONTROL OF SPACECRAFT WITH UNKNOWN

More information

Generation X. Attitude Control Systems (ACS) Aprille Ericsson Dave Olney Josephine San. July 27, 2000

Generation X. Attitude Control Systems (ACS) Aprille Ericsson Dave Olney Josephine San. July 27, 2000 Generation X Attitude Control Systems (ACS) Aprille Ericsson Dave Olney Josephine San July 27, 2000 ACS Overview Requirements Assumptions Disturbance Torque Assessment Component and Control Mode Recommendations

More information

Space Surveillance using Star Trackers. Part I: Simulations

Space Surveillance using Star Trackers. Part I: Simulations AAS 06-231 Space Surveillance using Star Trackers. Part I: Simulations Iohan Ettouati, Daniele Mortari, and Thomas Pollock Texas A&M University, College Station, Texas 77843-3141 Abstract This paper presents

More information

Experiments in Control of Rotational Mechanics

Experiments in Control of Rotational Mechanics International Journal of Automation, Control and Intelligent Systems Vol. 2, No. 1, 2016, pp. 9-22 http://www.aiscience.org/journal/ijacis ISSN: 2381-7526 (Print); ISSN: 2381-7534 (Online) Experiments

More information

Predictive Control of Gyroscopic-Force Actuators for Mechanical Vibration Damping

Predictive Control of Gyroscopic-Force Actuators for Mechanical Vibration Damping ARC Centre of Excellence for Complex Dynamic Systems and Control, pp 1 15 Predictive Control of Gyroscopic-Force Actuators for Mechanical Vibration Damping Tristan Perez 1, 2 Joris B Termaat 3 1 School

More information

Pierre Bigot 2 and Luiz C. G. de Souza 3

Pierre Bigot 2 and Luiz C. G. de Souza 3 INTERNATIONAL JOURNAL OF SYSTEMS APPLICATIONS, ENGINEERING & DEVELOPMENT Volume 8, 2014 Investigation of the State Dependent Riccati Equation (SDRE) adaptive control advantages for controlling non-linear

More information

Here represents the impulse (or delta) function. is an diagonal matrix of intensities, and is an diagonal matrix of intensities.

Here represents the impulse (or delta) function. is an diagonal matrix of intensities, and is an diagonal matrix of intensities. 19 KALMAN FILTER 19.1 Introduction In the previous section, we derived the linear quadratic regulator as an optimal solution for the fullstate feedback control problem. The inherent assumption was that

More information

Unit quaternion observer based attitude stabilization of a rigid spacecraft without velocity measurement

Unit quaternion observer based attitude stabilization of a rigid spacecraft without velocity measurement Proceedings of the 45th IEEE Conference on Decision & Control Manchester Grand Hyatt Hotel San Diego, CA, USA, December 3-5, 6 Unit quaternion observer based attitude stabilization of a rigid spacecraft

More information

ATTITUDE CONTROL MECHANIZATION TO DE-ORBIT SATELLITES USING SOLAR SAILS

ATTITUDE CONTROL MECHANIZATION TO DE-ORBIT SATELLITES USING SOLAR SAILS IAA-AAS-DyCoSS2-14-07-02 ATTITUDE CONTROL MECHANIZATION TO DE-ORBIT SATELLITES USING SOLAR SAILS Ozan Tekinalp, * Omer Atas INTRODUCTION Utilization of solar sails for the de-orbiting of satellites is

More information

Spacecraft Attitude Control with RWs via LPV Control Theory: Comparison of Two Different Methods in One Framework

Spacecraft Attitude Control with RWs via LPV Control Theory: Comparison of Two Different Methods in One Framework Trans. JSASS Aerospace Tech. Japan Vol. 4, No. ists3, pp. Pd_5-Pd_, 6 Spacecraft Attitude Control with RWs via LPV Control Theory: Comparison of Two Different Methods in One Framework y Takahiro SASAKI,),

More information

KINEMATIC EQUATIONS OF NONNOMINAL EULER AXIS/ANGLE ROTATION

KINEMATIC EQUATIONS OF NONNOMINAL EULER AXIS/ANGLE ROTATION IAA-AAS-DyCoSS -14-10-01 KINEMATIC EQUATIONS OF NONNOMINAL EULER AXIS/ANGLE ROTATION Emanuele L. de Angelis and Fabrizio Giulietti INTRODUCTION Euler axis/angle is a useful representation in many attitude

More information

Attitude Determination and. Attitude Control

Attitude Determination and. Attitude Control Attitude Determination and Placing the telescope in orbit is not the end of the story. It is necessary to point the telescope towards the selected targets, or to scan the selected sky area with the telescope.

More information

AS3010: Introduction to Space Technology

AS3010: Introduction to Space Technology AS3010: Introduction to Space Technology L E C T U R E 22 Part B, Lecture 22 19 April, 2017 C O N T E N T S Attitude stabilization passive and active. Actuators for three axis or active stabilization.

More information

Multi-Robotic Systems

Multi-Robotic Systems CHAPTER 9 Multi-Robotic Systems The topic of multi-robotic systems is quite popular now. It is believed that such systems can have the following benefits: Improved performance ( winning by numbers ) Distributed

More information

CHAPTER 4 CONVENTIONAL CONTROL FOR SATELLITE ATTITUDE

CHAPTER 4 CONVENTIONAL CONTROL FOR SATELLITE ATTITUDE 93 CHAPTER 4 CONVENTIONAL CONTROL FOR SATELLITE ATTITUDE 4.1 INTRODUCTION Attitude control is the process of achieving and maintaining an orientation in space. The orientation control of a rigid body has

More information

Satellite Attitude Determination with Attitude Sensors and Gyros using Steady-state Kalman Filter

Satellite Attitude Determination with Attitude Sensors and Gyros using Steady-state Kalman Filter Satellite Attitude Determination with Attitude Sensors and Gyros using Steady-state Kalman Filter Vaibhav V. Unhelkar, Hari B. Hablani Student, email: v.unhelkar@iitb.ac.in. Professor, email: hbhablani@aero.iitb.ac.in

More information

Design of Sliding Mode Attitude Control for Communication Spacecraft

Design of Sliding Mode Attitude Control for Communication Spacecraft Design of Sliding Mode Attitude Control for Communication Spacecraft Erkan Abdulhamitbilal 1 and Elbrous M. Jafarov 1 ISTAVIA Engineering, Istanbul Aeronautics and Astronautics Engineering, Istanbul Technical

More information

Extended Kalman Filter for Spacecraft Pose Estimation Using Dual Quaternions*

Extended Kalman Filter for Spacecraft Pose Estimation Using Dual Quaternions* Extended Kalman Filter for Spacecraft Pose Estimation Using Dual Quaternions* Nuno Filipe Michail Kontitsis 2 Panagiotis Tsiotras 3 Abstract Based on the highly successful Quaternion Multiplicative Extended

More information

Introduction to centralized control

Introduction to centralized control Industrial Robots Control Part 2 Introduction to centralized control Independent joint decentralized control may prove inadequate when the user requires high task velocities structured disturbance torques

More information

RELATIVE NAVIGATION FOR SATELLITES IN CLOSE PROXIMITY USING ANGLES-ONLY OBSERVATIONS

RELATIVE NAVIGATION FOR SATELLITES IN CLOSE PROXIMITY USING ANGLES-ONLY OBSERVATIONS (Preprint) AAS 12-202 RELATIVE NAVIGATION FOR SATELLITES IN CLOSE PROXIMITY USING ANGLES-ONLY OBSERVATIONS Hemanshu Patel 1, T. Alan Lovell 2, Ryan Russell 3, Andrew Sinclair 4 "Relative navigation using

More information

Stabilization of Angular Velocity of Asymmetrical Rigid Body. Using Two Constant Torques

Stabilization of Angular Velocity of Asymmetrical Rigid Body. Using Two Constant Torques Stabilization of Angular Velocity of Asymmetrical Rigid Body Using Two Constant Torques Hirohisa Kojima Associate Professor Department of Aerospace Engineering Tokyo Metropolitan University 6-6, Asahigaoka,

More information

CHAPTER 5 FUZZY LOGIC FOR ATTITUDE CONTROL

CHAPTER 5 FUZZY LOGIC FOR ATTITUDE CONTROL 104 CHAPTER 5 FUZZY LOGIC FOR ATTITUDE CONTROL 5.1 INTRODUCTION Fuzzy control is one of the most active areas of research in the application of fuzzy set theory, especially in complex control tasks, which

More information

Attitude dynamics and control

Attitude dynamics and control Attitude dynamics and control First AstroNet-II Training School "Astrodynamics of natural and artificial satellites: from regular to chaotic motions" Department of Mathematics, University of Roma Tor Vergata,

More information

OPTIMAL SPACECRAF1 ROTATIONAL MANEUVERS

OPTIMAL SPACECRAF1 ROTATIONAL MANEUVERS STUDIES IN ASTRONAUTICS 3 OPTIMAL SPACECRAF1 ROTATIONAL MANEUVERS JOHNL.JUNKINS Texas A&M University, College Station, Texas, U.S.A. and JAMES D.TURNER Cambridge Research, Division of PRA, Inc., Cambridge,

More information

3 Rigid Spacecraft Attitude Control

3 Rigid Spacecraft Attitude Control 1 3 Rigid Spacecraft Attitude Control Consider a rigid spacecraft with body-fixed frame F b with origin O at the mass centre. Let ω denote the angular velocity of F b with respect to an inertial frame

More information

MULTI PURPOSE MISSION ANALYSIS DEVELOPMENT FRAMEWORK MUPUMA

MULTI PURPOSE MISSION ANALYSIS DEVELOPMENT FRAMEWORK MUPUMA MULTI PURPOSE MISSION ANALYSIS DEVELOPMENT FRAMEWORK MUPUMA Felipe Jiménez (1), Francisco Javier Atapuerca (2), José María de Juana (3) (1) GMV AD., Isaac Newton 11, 28760 Tres Cantos, Spain, e-mail: fjimenez@gmv.com

More information

Attitude Control Strategy for HAUSAT-2 with Pitch Bias Momentum System

Attitude Control Strategy for HAUSAT-2 with Pitch Bias Momentum System SSC06-VII-5 Attitude Control Strategy for HAUSAT-2 with Pitch Bias Momentum System Young-Keun Chang, Seok-Jin Kang, Byung-Hoon Lee, Jung-on Choi, Mi-Yeon Yun and Byoung-Young Moon School of Aerospace and

More information

PRELIMINAJ3.:( 6/8/92 SOFTWARE REQUIREMENTS SPECIFICATION FOR THE DSPSE GUIDANCE, NAVIGATION, AND CONTROL CSCI. Prepared by

PRELIMINAJ3.:( 6/8/92 SOFTWARE REQUIREMENTS SPECIFICATION FOR THE DSPSE GUIDANCE, NAVIGATION, AND CONTROL CSCI. Prepared by PRELIMINAJ3.:( SOFTWARE REQUIREMENTS SPECIFICATION FOR THE DSPSE GUIDANCE, NAVIGATION, AND CONTROL CSCI Prepared by Space Applications Corporation 6/8/92.. 1 SCOPE 1.1 IDENTIFICATION 1.2 OVERVIEW This

More information

A NONLINEARITY MEASURE FOR ESTIMATION SYSTEMS

A NONLINEARITY MEASURE FOR ESTIMATION SYSTEMS AAS 6-135 A NONLINEARITY MEASURE FOR ESTIMATION SYSTEMS Andrew J. Sinclair,JohnE.Hurtado, and John L. Junkins The concept of nonlinearity measures for dynamical systems is extended to estimation systems,

More information

Nonlinear Predictive Control of Spacecraft

Nonlinear Predictive Control of Spacecraft Nonlinear Predictive Control of Spacecraft John L. Crassidis 1 F. Landis Markley obin C. Anthony 3 Stephen F. Andrews 3 Abstract. A new approach for the control of a spacecraft with large angle maneuvers

More information

Control of Mobile Robots

Control of Mobile Robots Control of Mobile Robots Regulation and trajectory tracking Prof. Luca Bascetta (luca.bascetta@polimi.it) Politecnico di Milano Dipartimento di Elettronica, Informazione e Bioingegneria Organization and

More information

3D Pendulum Experimental Setup for Earth-based Testing of the Attitude Dynamics of an Orbiting Spacecraft

3D Pendulum Experimental Setup for Earth-based Testing of the Attitude Dynamics of an Orbiting Spacecraft 3D Pendulum Experimental Setup for Earth-based Testing of the Attitude Dynamics of an Orbiting Spacecraft Mario A. Santillo, Nalin A. Chaturvedi, N. Harris McClamroch, Dennis S. Bernstein Department of

More information

Linear-Quadratic Optimal Control: Full-State Feedback

Linear-Quadratic Optimal Control: Full-State Feedback Chapter 4 Linear-Quadratic Optimal Control: Full-State Feedback 1 Linear quadratic optimization is a basic method for designing controllers for linear (and often nonlinear) dynamical systems and is actually

More information

Regenerative Power Optimal Reaction Wheel Attitude Control

Regenerative Power Optimal Reaction Wheel Attitude Control University of Colorado, Boulder CU Scholar Aerospace Engineering Sciences Graduate Theses & Dissertations Aerospace Engineering Sciences Spring 1-1-211 Regenerative Power Optimal Reaction Wheel Attitude

More information

Attitude Determination using Infrared Earth Horizon Sensors

Attitude Determination using Infrared Earth Horizon Sensors SSC14-VIII-3 Attitude Determination using Infrared Earth Horizon Sensors Tam Nguyen Department of Aeronautics and Astronautics, Massachusetts Institute of Technology 77 Massachusetts Avenue, Cambridge,

More information

Spinning Satellites Examples. ACS: Gravity Gradient. ACS: Single Spin

Spinning Satellites Examples. ACS: Gravity Gradient. ACS: Single Spin Attitude Determination and Attitude Control Placing the telescope in orbit is not the end of the story. It is necessary to point the telescope towards the selected targets, or to scan the selected sky

More information

Simplified Filtering Estimator for Spacecraft Attitude Determination from Phase Information of GPS Signals

Simplified Filtering Estimator for Spacecraft Attitude Determination from Phase Information of GPS Signals WCE 7, July - 4, 7, London, U.K. Simplified Filtering Estimator for Spacecraft Attitude Determination from Phase Information of GPS Signals S. Purivigraipong, Y. Hashida, and M. Unwin Abstract his paper

More information

Application of the state-dependent riccati equation and kalman filter techniques to the design of a satellite control system

Application of the state-dependent riccati equation and kalman filter techniques to the design of a satellite control system Shock and Vibration 19 (2012) 939 946 939 DOI 10.3233/SAV-2012-0701 IOS Press Application of the state-dependent riccati equation and kalman filter techniques to the design of a satellite control system

More information

Hybrid spacecraft attitude control system

Hybrid spacecraft attitude control system Int. Jnl. of Multiphysics Volume 1 Number 2 2007 221 Hybrid spacecraft attitude control system Renuganth Varatharajoo *, Ramly Ajir, Tamizi Ahmad Department of Aerospace Engineering, University Putra Malaysia,

More information

Spacecraft Attitude Dynamics for Undergraduates

Spacecraft Attitude Dynamics for Undergraduates Session 1123 Spacecraft Attitude Dynamics for Undergraduates Dr. Rachel Shinn Embry Riddle Aeronautical University, Prescott, AZ Abstract Teaching spacecraft attitude dynamics to undergraduate students

More information

A Close Examination of Multiple Model Adaptive Estimation Vs Extended Kalman Filter for Precision Attitude Determination

A Close Examination of Multiple Model Adaptive Estimation Vs Extended Kalman Filter for Precision Attitude Determination A Close Examination of Multiple Model Adaptive Estimation Vs Extended Kalman Filter for Precision Attitude Determination Quang M. Lam LexerdTek Corporation Clifton, VA 4 John L. Crassidis University at

More information

Research Article Shorter Path Design and Control for an Underactuated Satellite

Research Article Shorter Path Design and Control for an Underactuated Satellite Hindawi International Journal of Aerospace Engineering Volume 27 Article ID 8536732 9 pages https://doi.org/.55/27/8536732 Research Article Shorter Path Design and Control for an Underactuated Satellite

More information

MISSION PERFORMANCE MEASURES FOR SPACECRAFT FORMATION FLYING

MISSION PERFORMANCE MEASURES FOR SPACECRAFT FORMATION FLYING MISSION PERFORMANCE MEASURES FOR SPACECRAFT FORMATION FLYING Steven P. Hughes and Christopher D. Hall Aerospace and Ocean Engineering Virginia Polytechnic Institute and State University ABSTRACT Clusters

More information

Linear State Feedback Controller Design

Linear State Feedback Controller Design Assignment For EE5101 - Linear Systems Sem I AY2010/2011 Linear State Feedback Controller Design Phang Swee King A0033585A Email: king@nus.edu.sg NGS/ECE Dept. Faculty of Engineering National University

More information

Investigation of the Attitude Error Vector Reference Frame in the INS EKF

Investigation of the Attitude Error Vector Reference Frame in the INS EKF Investigation of the Attitude Error Vector Reference Frame in the INS EKF Stephen Steffes, Jan Philipp Steinbach, and Stephan Theil Abstract The Extended Kalman Filter is used extensively for inertial

More information

ELEC4631 s Lecture 2: Dynamic Control Systems 7 March Overview of dynamic control systems

ELEC4631 s Lecture 2: Dynamic Control Systems 7 March Overview of dynamic control systems ELEC4631 s Lecture 2: Dynamic Control Systems 7 March 2011 Overview of dynamic control systems Goals of Controller design Autonomous dynamic systems Linear Multi-input multi-output (MIMO) systems Bat flight

More information

AIM RS: Radio Science Investigation with AIM

AIM RS: Radio Science Investigation with AIM Prepared by: University of Bologna Ref. number: ALMARS012016 Version: 1.0 Date: 08/03/2017 PROPOSAL TO ESA FOR AIM RS Radio Science Investigation with AIM ITT Reference: Partners: Radio Science and Planetary

More information

Robust Adaptive Attitude Control of a Spacecraft

Robust Adaptive Attitude Control of a Spacecraft Robust Adaptive Attitude Control of a Spacecraft AER1503 Spacecraft Dynamics and Controls II April 24, 2015 Christopher Au Agenda Introduction Model Formulation Controller Designs Simulation Results 2

More information

Subject: Optimal Control Assignment-1 (Related to Lecture notes 1-10)

Subject: Optimal Control Assignment-1 (Related to Lecture notes 1-10) Subject: Optimal Control Assignment- (Related to Lecture notes -). Design a oil mug, shown in fig., to hold as much oil possible. The height and radius of the mug should not be more than 6cm. The mug must

More information

COUPLED ORBITAL AND ATTITUDE CONTROL SIMULATION

COUPLED ORBITAL AND ATTITUDE CONTROL SIMULATION COUPLED ORBITAL AND ATTITUDE CONTROL SIMULATION Scott E. Lennox AOE 5984: Advanced Attitude Spacecraft Dynamics and Control December 12, 23 INTRODUCTION In the last few years the space industry has started

More information

arxiv: v1 [math.ds] 18 Nov 2008

arxiv: v1 [math.ds] 18 Nov 2008 arxiv:0811.2889v1 [math.ds] 18 Nov 2008 Abstract Quaternions And Dynamics Basile Graf basile.graf@epfl.ch February, 2007 We give a simple and self contained introduction to quaternions and their practical

More information

Sensors: a) Gyroscope. Micro Electro-Mechanical (MEM) Gyroscopes: (MEM) Gyroscopes. Needs:

Sensors: a) Gyroscope. Micro Electro-Mechanical (MEM) Gyroscopes: (MEM) Gyroscopes. Needs: Sensors: Needs: Data redundancy Data for both situations: eclipse and sun Question of sampling frequency Location and size/weight Ability to resist to environment Low consumption Low price a) Gyroscope

More information

Fundamentals of High Accuracy Inertial Navigation Averil B. Chatfield Table of Contents

Fundamentals of High Accuracy Inertial Navigation Averil B. Chatfield Table of Contents Navtech Part #2440 Preface Fundamentals of High Accuracy Inertial Navigation Averil B. Chatfield Table of Contents Chapter 1. Introduction...... 1 I. Forces Producing Motion.... 1 A. Gravitation......

More information

Automated Tuning of the Nonlinear Complementary Filter for an Attitude Heading Reference Observer

Automated Tuning of the Nonlinear Complementary Filter for an Attitude Heading Reference Observer Automated Tuning of the Nonlinear Complementary Filter for an Attitude Heading Reference Observer Oscar De Silva, George K.I. Mann and Raymond G. Gosine Faculty of Engineering and Applied Sciences, Memorial

More information

A Concept of Nanosatellite Small Fleet for Earth Observation

A Concept of Nanosatellite Small Fleet for Earth Observation A Concept of Nanosatellite Small Fleet for Earth Observation Prof. Janusz Narkiewicz jnark@meil.pw.edu.pl Sebastian Topczewski stopczewski@meil.pw.edu.pl Mateusz Sochacki msochacki@meil.pw.edu.pl 10-11

More information

Sliding Mode Control Strategies for Spacecraft Rendezvous Maneuvers

Sliding Mode Control Strategies for Spacecraft Rendezvous Maneuvers Osaka University March 15, 2018 Sliding Mode Control Strategies for Spacecraft Rendezvous Maneuvers Elisabetta Punta CNR-IEIIT, Italy Problem Statement First Case Spacecraft Model Position Dynamics Attitude

More information

New Worlds Observer Final Report Appendix J. Appendix J: Trajectory Design and Orbit Determination Lead Author: Karen Richon

New Worlds Observer Final Report Appendix J. Appendix J: Trajectory Design and Orbit Determination Lead Author: Karen Richon Appendix J: Trajectory Design and Orbit Determination Lead Author: Karen Richon The two NWO spacecraft will orbit about the libration point created by the Sun and Earth/Moon barycenter at the far side

More information

Introduction to centralized control

Introduction to centralized control ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Control Part 2 Introduction to centralized control Independent joint decentralized control may prove inadequate when the user requires high task

More information

COVARIANCE DETERMINATION, PROPAGATION AND INTERPOLATION TECHNIQUES FOR SPACE SURVEILLANCE. European Space Surveillance Conference 7-9 June 2011

COVARIANCE DETERMINATION, PROPAGATION AND INTERPOLATION TECHNIQUES FOR SPACE SURVEILLANCE. European Space Surveillance Conference 7-9 June 2011 COVARIANCE DETERMINATION, PROPAGATION AND INTERPOLATION TECHNIQUES FOR SPACE SURVEILLANCE European Space Surveillance Conference 7-9 June 2011 Pablo García (1), Diego Escobar (1), Alberto Águeda (1), Francisco

More information

Lecture Module 5: Introduction to Attitude Stabilization and Control

Lecture Module 5: Introduction to Attitude Stabilization and Control 1 Lecture Module 5: Introduction to Attitude Stabilization and Control Lectures 1-3 Stability is referred to as a system s behaviour to external/internal disturbances (small) in/from equilibrium states.

More information

Control Systems I. Lecture 2: Modeling. Suggested Readings: Åström & Murray Ch. 2-3, Guzzella Ch Emilio Frazzoli

Control Systems I. Lecture 2: Modeling. Suggested Readings: Åström & Murray Ch. 2-3, Guzzella Ch Emilio Frazzoli Control Systems I Lecture 2: Modeling Suggested Readings: Åström & Murray Ch. 2-3, Guzzella Ch. 2-3 Emilio Frazzoli Institute for Dynamic Systems and Control D-MAVT ETH Zürich September 29, 2017 E. Frazzoli

More information

UAV Navigation: Airborne Inertial SLAM

UAV Navigation: Airborne Inertial SLAM Introduction UAV Navigation: Airborne Inertial SLAM Jonghyuk Kim Faculty of Engineering and Information Technology Australian National University, Australia Salah Sukkarieh ARC Centre of Excellence in

More information

c 2009 John Gregory Warner

c 2009 John Gregory Warner c 2009 John Gregory Warner ATTITUDE DETERMINATION AND CONTROL OF NANO-SATELLITES BY JOHN GREGORY WARNER THESIS Submitted in partial fulfillment of the requirements for the degree of Master of Science in

More information

On Sun-Synchronous Orbits and Associated Constellations

On Sun-Synchronous Orbits and Associated Constellations On Sun-Synchronous Orbits and Associated Constellations Daniele Mortari, Matthew P. Wilkins, and Christian Bruccoleri Department of Aerospace Engineering, Texas A&M University, College Station, TX 77843,

More information

Homework Solution # 3

Homework Solution # 3 ECSE 644 Optimal Control Feb, 4 Due: Feb 17, 4 (Tuesday) Homework Solution # 3 1 (5%) Consider the discrete nonlinear control system in Homework # For the optimal control and trajectory that you have found

More information

Attitude Control Simulator for the Small Satellite and Its Validation by On-orbit Data of QSAT-EOS

Attitude Control Simulator for the Small Satellite and Its Validation by On-orbit Data of QSAT-EOS SSC17-P1-17 Attitude Control Simulator for the Small Satellite and Its Validation by On-orbit Data of QSAT-EOS Masayuki Katayama, Yuta Suzaki Mitsubishi Precision Company Limited 345 Kamikmachiya, Kamakura

More information

Structure and algorithms of motion control system's software of the small spacecraft

Structure and algorithms of motion control system's software of the small spacecraft Structure and algorithms of motion control system's software of the small spacecraft Filatov A.V., Progress Space Rocket Centre, Samara Tkachenko I.S., Tyugashev A.A., Sopchenko E.V. Samara State Aerospace

More information

(3.1) a 2nd-order vector differential equation, as the two 1st-order vector differential equations (3.3)

(3.1) a 2nd-order vector differential equation, as the two 1st-order vector differential equations (3.3) Chapter 3 Kinematics As noted in the Introduction, the study of dynamics can be decomposed into the study of kinematics and kinetics. For the translational motion of a particle of mass m, this decomposition

More information

Problem 1: Ship Path-Following Control System (35%)

Problem 1: Ship Path-Following Control System (35%) Problem 1: Ship Path-Following Control System (35%) Consider the kinematic equations: Figure 1: NTNU s research vessel, R/V Gunnerus, and Nomoto model: T ṙ + r = Kδ (1) with T = 22.0 s and K = 0.1 s 1.

More information

HIGH-ORDER STATE FEEDBACK GAIN SENSITIVITY CALCULATIONS USING COMPUTATIONAL DIFFERENTIATION

HIGH-ORDER STATE FEEDBACK GAIN SENSITIVITY CALCULATIONS USING COMPUTATIONAL DIFFERENTIATION (Preprint) AAS 12-637 HIGH-ORDER STATE FEEDBACK GAIN SENSITIVITY CALCULATIONS USING COMPUTATIONAL DIFFERENTIATION Ahmad Bani Younes, James Turner, Manoranjan Majji, and John Junkins INTRODUCTION A nonlinear

More information

Aerodynamic Lift and Drag Effects on the Orbital Lifetime Low Earth Orbit (LEO) Satellites

Aerodynamic Lift and Drag Effects on the Orbital Lifetime Low Earth Orbit (LEO) Satellites Aerodynamic Lift and Drag Effects on the Orbital Lifetime Low Earth Orbit (LEO) Satellites I. Introduction Carlos L. Pulido Department of Aerospace Engineering Sciences University of Colorado Boulder Abstract

More information

5.12 The Aerodynamic Assist Trajectories of Vehicles Propelled by Solar Radiation Pressure References...

5.12 The Aerodynamic Assist Trajectories of Vehicles Propelled by Solar Radiation Pressure References... 1 The Two-Body Problem... 1 1.1 Position of the Problem... 1 1.2 The Conic Sections and Their Geometrical Properties... 12 1.3 The Elliptic Orbits... 20 1.4 The Hyperbolic and Parabolic Trajectories...

More information