HokieSatSimulation.cpp

Go to the documentation of this file.
00001 
00002 
00008 
00010 
00011 
00012 #include "HokieSatSimulation.h"
00013 
00019 int main()
00020 {
00021     Orbit* pHokiesatOrbit = SetupOrbit();
00022     Attitude* pHokiesatAttitude = SetupAttitude();
00023     
00024     // Setup Propagator
00025         NumericPropagator* pHokiesatPropagator = SetupPropagator();
00026         pHokiesatOrbit->SetPropagator(pHokiesatPropagator);
00027         pHokiesatAttitude->SetPropagator(pHokiesatPropagator);
00028 
00029     // Setup external environment
00030         Environment* pEarthEnv = SetupEnvironment(pHokiesatAttitude);
00031         pHokiesatOrbit->SetEnvironment(pEarthEnv);
00032         pHokiesatAttitude->SetEnvironment(pEarthEnv);
00033 
00034     // Integration Times
00035         double propTime = 20; // mins
00036             cout << "Propagation time (mins): " << flush;
00037             cin >> propTime;
00038         double propStep = 60; // s
00039             cout << "Propagation step (secs): " << flush;
00040             cin >> propStep;
00041         vector<ssfTime> integrationTimes;
00042         ssfTime begin(0);
00043         ssfTime end(begin + propStep);
00044         integrationTimes.push_back(begin);
00045         integrationTimes.push_back(end);
00046         
00047     // Output the current state properties
00048         cout << "PropTime = " << begin.GetSeconds() << " s -> " << end.GetSeconds() << " s" << endl;
00049         cout << "Orbit State: " << ~pHokiesatOrbit->GetStateObject().GetStateRepresentation()->GetPositionVelocity();
00050         cout << "Attitude State: " << ~pHokiesatAttitude->GetStateObject().GetState() << endl;
00051 
00052     // Integrate over the desired time interval
00053         tick();
00054         pHokiesatPropagator->Propagate(integrationTimes, pHokiesatOrbit->GetStateObject().GetStateRepresentation()->GetPositionVelocity(), pHokiesatAttitude->GetStateObject().GetState());                            
00055 
00056         for (int ii = 0; ii < propTime*60/propStep ; ++ii)
00057         {
00058             // Integrate again
00059             integrationTimes[0] = integrationTimes[1];
00060             integrationTimes[1] = integrationTimes[0] + propStep;
00061             //cout << integrationTimes[0] << " -> " << integrationTimes[1] << endl;
00062             pHokiesatPropagator->Propagate(integrationTimes, pHokiesatOrbit->GetStateObject().GetStateRepresentation()->GetPositionVelocity(), pHokiesatAttitude->GetStateObject().GetState());
00063             if((ii % 100) < 5)
00064                 cout << integrationTimes[0].GetSeconds() << ", ";
00065         }
00066         cout << endl;
00067         ssfSeconds calcTime = tock();
00068         cout << "finished propagating " << propTime*60 << " sim-seconds in " << calcTime << " real-seconds." << endl;     
00069     // Plot the state history
00070         Matrix orbitHistory = pHokiesatOrbit->GetHistoryObject().GetHistory();
00071         Matrix orbitPlotting = orbitHistory(_,_(MatrixIndexBase+1,MatrixIndexBase+3));
00072         Matrix attitudeHistory = pHokiesatAttitude->GetHistoryObject().GetHistory();
00073         Matrix attitudePlotting = attitudeHistory(_,_(MatrixIndexBase,MatrixIndexBase+4));
00074 
00075         Plot3D(orbitPlotting);
00076         Plot2D(attitudePlotting);
00077    
00078     // Store the output to file
00079         ofstream ofile;
00080         ofile.open("OrbitHistory.dat");
00081         ofile << pHokiesatOrbit->GetHistoryObject().GetHistory();
00082         ofile.close();
00083     
00084         ofile.open("AttitudeHistory.dat");
00085         ofile << pHokiesatAttitude->GetHistoryObject().GetHistory();
00086         ofile.close();
00087 
00088     return 0;
00089                             
00090 }
00091 
00092 // *************************
00093 // ****** ENVIRONMENT ****** 
00094 // *************************
00095 Environment* SetupEnvironment(Attitude* pSatAttitude)
00096 {
00097     // ENVIRONMENT TESTING
00098     Environment* pEarthEnv = new Environment;
00099     EarthCentralBody *pCBEarth = new EarthCentralBody;
00100     pEarthEnv->SetCentralBody(pCBEarth);
00101     
00102     // Add Gravity force function
00103         EnvFunction TwoBodyGravity(&GravityForceFunction);
00104         double *mu = new double(pCBEarth->GetGravitationalParameter());
00105         TwoBodyGravity.AddParameter(reinterpret_cast<void*>(mu), 1);
00106         pEarthEnv->AddForceFunction(TwoBodyGravity);
00107     
00108     cout << "Add Drag? (y or n): " << flush;
00109     char answer;
00110     cin >> answer;
00111     if(answer == 'y')
00112     {
00113         // Add Drag Force Function
00114         EnvFunction DragForce(&SimpleAerodynamicDragForce);
00115         double *BC = new double(2);
00116         DragForce.AddParameter(reinterpret_cast<void*>(BC), 1);
00117         double *rho = new double(1.13 * pow(static_cast<double>(10), static_cast<double>(-12))); // kg/m^3
00118         DragForce.AddParameter(reinterpret_cast<void*>(rho), 2);
00119         pEarthEnv->AddForceFunction(DragForce);
00120     }
00121     // Add Gravity torque function
00122     
00123         EnvFunction GGTorque(&GravityGradientTorque);
00124         Matrix *MOI = new Matrix(pSatAttitude->GetParameters()(_(1,3),_));
00125         GGTorque.AddParameter(reinterpret_cast<void*>(MOI), 1);
00126         GGTorque.AddParameter(reinterpret_cast<void*>(mu), 2);
00127         pEarthEnv->AddTorqueFunction(GGTorque);
00128     
00129     // Assign Magnetic Model
00130         pCBEarth->SetMagneticModel(new TiltedDipoleMagneticModel);
00131     return pEarthEnv;
00132 }
00133 
00134 // *************************
00135 // ****** PROPAGATOR ******* 
00136 // ************************* 
00137 NumericPropagator* SetupPropagator()
00138 {
00139     CombinedNumericPropagator* pSatProp = new CombinedNumericPropagator;
00140     
00141     // Create & setup the integator
00142         // Setup an integrator and any special parameters
00143     RungeKuttaFehlbergIntegrator* orbitIntegrator = new RungeKuttaFehlbergIntegrator; 
00144     RungeKuttaFehlbergIntegrator* attitudeIntegrator = new RungeKuttaFehlbergIntegrator; 
00145 
00146     orbitIntegrator->SetTolerance(pow(10.,-7.));
00147     orbitIntegrator->SetStepSizes(0.01, 300);
00148     pSatProp->SetOrbitIntegrator(orbitIntegrator);
00149     attitudeIntegrator->SetTolerance(pow(10.,-7.));
00150     attitudeIntegrator->SetStepSizes(0.01, 5);
00151     pSatProp->SetAttitudeIntegrator(attitudeIntegrator);
00152     
00153     return pSatProp;
00154 }
00155 
00156 // *************************
00157 // ********* ORBIT ********* 
00158 // ************************* 
00159 Orbit* SetupOrbit()
00160 {
00161     Orbit* pSatOrbit = new Orbit;
00162     
00163     // Create & initialize the orbit
00164     OrbitState SatOrbitState;
00165     SatOrbitState.SetStateRepresentation(new PositionVelocity);
00166     SatOrbitState.SetOrbitFrame(new OrbitFrameIJK);
00167     Vector initPV(6);
00168         // Space station
00169         initPV(VectorIndexBase+0) = -5776.6; // km
00170         initPV(VectorIndexBase+1) = -157; // km       
00171         initPV(VectorIndexBase+2) = 3496.9; // km    
00172         initPV(VectorIndexBase+3) = -2.595;  // km/s
00173         initPV(VectorIndexBase+4) = -5.651;  // km/s        
00174         initPV(VectorIndexBase+5) = -4.513; // km/s
00175     SatOrbitState.SetState(initPV);
00176     pSatOrbit->SetStateObject(SatOrbitState);
00177     
00178     pSatOrbit->SetDynamicsEq(&TwoBodyDynamics);
00179     pSatOrbit->SetStateConversion(&PositionVelocityConvFunc);
00180 
00181     return pSatOrbit;
00182 }
00183 
00184 
00185 // *************************
00186 // ******* ATTITUDE ******** 
00187 // ************************* 
00188 Attitude* SetupAttitude()
00189 {
00190     Attitude* pSatAttitude = new Attitude;
00191     
00192     AttitudeState SatAttState;
00193     SatAttState.SetRotation(Rotation(Quaternion(0,0,0,1)));
00194     Vector initAngVelVector(3);
00195         initAngVelVector(1) = 0;
00196     SatAttState.SetAngularVelocity(initAngVelVector);
00197 
00198     pSatAttitude->SetStateObject(SatAttState);
00199     pSatAttitude->SetDynamicsEq(&AttituteDynamics_QuaternionAngVel);
00200     pSatAttitude->SetStateConversion(&QuaternionAngVelConvFunc);
00201 
00202     // Create the matrix of parameters needed for the RHS
00203     Matrix MOI(3,3);
00204         MOI(1,1) =  0.4084; MOI(1,2) =  0.0046; MOI(1,3) = 0.0;
00205         MOI(2,1) =  0.0046; MOI(2,2) =  0.3802; MOI(2,3) = 0.0;
00206         MOI(3,1) =  0.0;    MOI(3,2) =  0.0;    MOI(3,3) = 0.4530;
00207 
00208     MOI = eye(3);
00209         MOI(1,1) = 2; MOI(2,2) = 2; MOI(3,3) = 10;
00210     Matrix params(6,3);
00211         params(_(1,3),_) = MOI;
00212         params(_(4,6),_) = MOI.inverse();
00213     
00214     pSatAttitude->SetParameters(params);
00215     
00216     return pSatAttitude;
00217     
00218 }
00219 
00220 Vector ControlTorques(const ssfTime &_currentTime, const OrbitState  &_currentOrbitState, const AttitudeState &_currentAttitudeState, const EnvFuncParamaterType &_parameterList) // HYK
00221 {
00222   /* This function takes the current and desired attitudes (orbital to body)
00223    * and returns the needed control torque (in N-m)
00224    */
00225    /*
00226   static Matrix Kp(3,3);        // gain on quaternion
00227   static Matrix Kd(3,3);        // gain on angular velocity
00228   static Matrix qCurrent(4,1);  // current quaternion (orbital to body)
00229   static Matrix qDesired(4,1);  // desired quaternion (orbital to body)
00230   static Matrix wCurrent(3,1);  // current angular velocity (orbital to body, rad/s)
00231   static Matrix wDesired(3,1);  // desired angular velocity (orbital to body, rad/s)
00232   static Matrix qError(4,1);    // the error quaternion (desired to body)
00233   static Matrix qErrAxis(3,1);  // Euler axis for desired to body rotation
00234   static double qError4;         // fourth entry of error quaternion
00235   static Matrix wError;          // Angular Velocity error
00236   static Matrix sigma(3,1);     // scaled error quaternion
00237 
00238   static Matrix Inertia(3,3);    // Moments of inertia, kg-m^2
00239 
00240 
00241 
00242   qCurrent = CurrentAttState[mslice(0,0,4,1)];
00243   qDesired = DesAttState[mslice(0,0,4,1)]; //HYKIM Oct 15
00244   wCurrent = CurrentAttState[mslice(4,0,3,1)];
00245   wDesired = DesAttState[mslice(4,0,3,1)];
00246 
00247   qError = ATT_qMult(qCurrent, qDesired);
00248 
00249   wError = wCurrent - wDesired;
00250   qErrAxis = qError[mslice(0,0,3,1)];
00251   qError4 = qError(3,0);
00252 
00253   Kd = .02*eye(3);
00254   Kp = 0.0006*eye(3);
00255 
00256   Matrix Torque_r(3,1);
00257 
00258 
00259       sigma = qErrAxis / (1 + qError4);
00260       Torque_r = -Kp * sigma* (eye(1) + ~sigma * sigma) - Kd * wError;
00261 
00262   Matrix B(3,1);
00263   B = ATT1_CalcG(epoch, count);  // HYK
00264   //B = B / B.norm2();
00265   //Torque = Torque_r - (~Torque_r*B)*B;
00266   Matrix K(3,6);
00267 
00268  K(1,1) =  0.040424; K(1,2) =  0.000065; K(1,3) =  0.000110; K(1,3) =  30.393883; K(1,4) = -0.671557;  K(1,5) = -0.233840; 
00269  K(2,1) = -0.000724; K(2,2) =  0.030161; K(2,3) = -0.022378; K(2,3) = -1.024919;  K(2,4) =  34.678584; K(2,5) = -10.027221; 
00270  K(3,1) = -0.000370; K(3,2) =  0.020404; K(3,3) =  0.019692; K(3,3) = -0.326869;  K(3,4) = -1.073717;  K(3,5) =  24.430588;
00271 
00272   Matrix dx(6,1), gm(6,1), Gt(6,3);
00273 
00274 
00275 
00276   dx[mslice(0,0,3,1)] = qErrAxis;
00277   dx[mslice(3,0,3,1)] = wError; 
00278 
00279         Matrix Rto(3,3), qbt(4,1), wbt(3,1) ;
00280         Matrix temp5(3,1);
00281         Rto = ATT_q2R(qDesired);
00282         qbt = ATT_itzhackR2q(ATT_q2R(qCurrent)*~Rto);
00283 
00284         temp5=  qbt[mslice(0,0,3,1)];
00285         //cout<<"up="<<dx<<endl;
00286         dx[mslice(0,0,3,1)] = temp5;
00287         dx[mslice(3,0,3,1)] = wCurrent; 
00288         //cout<<"down="<<dx<<endl;
00289 
00290   Gt[mslice(3,0,3,3)] = -(1.0 / B.norm2()) * skew(B) * skew(B);
00291   gm = -Gt * K * dx;
00292   Torque  = gm[mslice(3,0,3,1)];
00293 //  Torque = ATT_q2R(qCurrent) * Torque;
00294 
00295 
00296 
00297   if (Torque.norm2() > MAXTORQUE)
00298     {
00299       Torque = Torque / Torque.norm2() * MAXTORQUE;
00300     }
00301 
00302   return ATT_TORQUE_VALID;
00303 */
00304     return Vector(3);
00305 }
00306 // Do not change the comments below - they will be added automatically by CVS
00307 /*****************************************************************************
00308 *       $Log: HokieSatSimulation.cpp,v $
00309 *       Revision 1.4  2003/06/12 23:05:55  nilspace
00310 *       Works.
00311 *       
00312 *       Revision 1.3  2003/06/12 21:01:48  nilspace
00313 *       Fixed GG torque MOI parameter.
00314 *       
00315 *       Revision 1.2  2003/06/12 20:48:10  nilspace
00316 *       Asks user for times.
00317 *       
00318 *       Revision 1.1  2003/06/12 18:06:06  nilspace
00319 *       Initial submission.
00320 *       
00321 *       Revision 1.4  2003/05/27 17:47:13  nilspace
00322 *       Updated example to have seperate orbit & attitude integrators.
00323 *       
00324 *       Revision 1.3  2003/05/20 19:24:43  nilspace
00325 *       Updated.
00326 *       
00327 *       Revision 1.2  2003/05/13 18:57:32  nilspace
00328 *       Clened up to work with new Propagators.
00329 *       
00330 *       Revision 1.1  2003/05/01 02:42:47  nilspace
00331 *       New propagation test file.
00332 *       
00333 *
00334 ******************************************************************************/
00335 
00336                         

Generated on Wed Aug 6 12:58:46 2003 for Open-Sessame Framework by doxygen1.3