]> git.mxchange.org Git - flightgear.git/commitdiff
JSBSim sync
authorbcoconni <bcoconni>
Sun, 18 May 2014 11:39:31 +0000 (13:39 +0200)
committerbcoconni <bcoconni>
Sun, 18 May 2014 11:39:31 +0000 (13:39 +0200)
79 files changed:
src/FDM/JSBSim/FGFDMExec.cpp
src/FDM/JSBSim/FGFDMExec.h
src/FDM/JSBSim/initialization/FGInitialCondition.cpp
src/FDM/JSBSim/initialization/FGInitialCondition.h
src/FDM/JSBSim/initialization/FGLinearization.cpp
src/FDM/JSBSim/initialization/FGSimplexTrim.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/initialization/FGTrim.cpp
src/FDM/JSBSim/initialization/FGTrim.h
src/FDM/JSBSim/initialization/FGTrimmer.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/input_output/FGGroundCallback.h
src/FDM/JSBSim/input_output/FGOutputFG.cpp
src/FDM/JSBSim/input_output/FGOutputFile.cpp
src/FDM/JSBSim/input_output/FGOutputFile.h
src/FDM/JSBSim/input_output/FGOutputSocket.cpp
src/FDM/JSBSim/input_output/FGOutputTextFile.cpp
src/FDM/JSBSim/input_output/FGScript.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/input_output/FGXMLElement.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/input_output/FGXMLElement.h [changed mode: 0755->0644]
src/FDM/JSBSim/input_output/FGXMLFileRead.h [changed mode: 0755->0644]
src/FDM/JSBSim/input_output/FGXMLParse.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/input_output/string_utilities.h
src/FDM/JSBSim/math/FGFunction.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGModelFunctions.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGModelFunctions.h [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGNelderMead.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGPropertyValue.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGPropertyValue.h [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGRealValue.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/math/FGStateSpace.cpp
src/FDM/JSBSim/models/FGAerodynamics.cpp
src/FDM/JSBSim/models/FGAircraft.cpp
src/FDM/JSBSim/models/FGAtmosphere.cpp
src/FDM/JSBSim/models/FGAuxiliary.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/FGExternalForce.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/FGExternalReactions.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/FGExternalReactions.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/FGFCS.cpp
src/FDM/JSBSim/models/FGFCSChannel.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/FGGroundReactions.cpp
src/FDM/JSBSim/models/FGInertial.cpp
src/FDM/JSBSim/models/FGInput.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/FGLGear.cpp
src/FDM/JSBSim/models/FGMassBalance.cpp
src/FDM/JSBSim/models/FGMassBalance.h
src/FDM/JSBSim/models/FGPropagate.cpp
src/FDM/JSBSim/models/FGPropagate.h
src/FDM/JSBSim/models/FGPropulsion.cpp
src/FDM/JSBSim/models/FGPropulsion.h
src/FDM/JSBSim/models/atmosphere/FGMSIS.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/atmosphere/FGMars.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/atmosphere/FGStandardAtmosphere.cpp
src/FDM/JSBSim/models/atmosphere/FGWinds.cpp
src/FDM/JSBSim/models/atmosphere/FGWinds.h
src/FDM/JSBSim/models/flight_control/FGAccelerometer.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGAccelerometer.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGActuator.cpp
src/FDM/JSBSim/models/flight_control/FGAngles.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGAngles.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGDistributor.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGDistributor.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGFCSComponent.h
src/FDM/JSBSim/models/flight_control/FGFCSFunction.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGFCSFunction.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGGyro.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGGyro.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGMagnetometer.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGMagnetometer.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGPID.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGPID.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGSensor.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGSensor.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGSensorOrientation.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGWaypoint.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/flight_control/FGWaypoint.h [changed mode: 0755->0644]
src/FDM/JSBSim/models/propulsion/FGRocket.cpp
src/FDM/JSBSim/models/propulsion/FGTank.cpp
src/FDM/JSBSim/models/propulsion/FGTank.h
src/FDM/JSBSim/models/propulsion/FGTurboProp.cpp [changed mode: 0755->0644]
src/FDM/JSBSim/models/propulsion/FGTurboProp.h [changed mode: 0755->0644]

index 2f05d2f1d13e9090272f70ad1f1bb7dbb3cf3bbe..6d07c01e661cb8368a877757dd67af1dd6332f8a 100644 (file)
@@ -64,6 +64,7 @@ INCLUDES
 #include "models/FGInput.h"
 #include "models/FGOutput.h"
 #include "initialization/FGInitialCondition.h"
+#include "initialization/FGTrim.h"
 #include "initialization/FGSimplexTrim.h"
 #include "initialization/FGLinearization.h"
 #include "input_output/FGPropertyManager.h"
@@ -75,7 +76,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGFDMExec.cpp,v 1.154 2014/01/13 10:45:59 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGFDMExec.cpp,v 1.161 2014/05/17 15:35:53 jberndt Exp $");
 IDENT(IdHdr,ID_FDMEXEC);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -89,10 +90,11 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root, unsigned int* fdmctr) : Root(root)
 {
   Frame           = 0;
   Error           = 0;
-  SetGroundCallback(new FGDefaultGroundCallback());
+  //SetGroundCallback(new FGDefaultGroundCallback());
   IC              = 0;
   Trim            = 0;
   Script          = 0;
+  disperse        = 0;
 
   RootDir = "";
 
@@ -139,6 +141,17 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root, unsigned int* fdmctr) : Root(root)
 
   FGPropertyNode* instanceRoot = Root->GetNode("/fdm/jsbsim",IdFDM,true);
   instance = new FGPropertyManager(instanceRoot);
+
+  try {
+    char* num = getenv("JSBSIM_DISPERSE");
+    if (num) {
+      if (atoi(num) != 0) disperse = 1;  // set dispersions on
+    }
+  } catch (...) {                        // if error set to false
+    disperse = 0;
+    std::cerr << "Could not process JSBSIM_DISPERSIONS environment variable: Assumed NO dispersions." << endl;
+  }
+
   Debug(0);
   // this is to catch errors in binding member functions to the property tree.
   try {
@@ -153,13 +166,12 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root, unsigned int* fdmctr) : Root(root)
 
   Constructing = true;
   typedef int (FGFDMExec::*iPMF)(void) const;
-//  typedef double (FGFDMExec::*dPMF)(void) const;
-//  typedef unsigned int (FGFDMExec::*uiPMF)(void) const;
 //  instance->Tie("simulation/do_trim_analysis", this, (iPMF)0, &FGFDMExec::DoTrimAnalysis, false);
   instance->Tie("simulation/do_simple_trim", this, (iPMF)0, &FGFDMExec::DoTrim, false);
   instance->Tie("simulation/do_simplex_trim", this, (iPMF)0, &FGFDMExec::DoSimplexTrim);
   instance->Tie("simulation/do_linearization", this, (iPMF)0, &FGFDMExec::DoLinearization);
-  instance->Tie("simulation/reset", (int*)&ResetMode);
+  instance->Tie("simulation/reset", this, (iPMF)0, &FGFDMExec::ResetToInitialConditions, false);
+  instance->Tie("simulation/disperse", this, &FGFDMExec::GetDisperse);
   instance->Tie("simulation/randomseed", this, (iPMF)0, &FGFDMExec::SRand, false);
   instance->Tie("simulation/terminate", (int *)&Terminate);
   instance->Tie("simulation/sim-time-sec", this, &FGFDMExec::GetSimTime);
@@ -294,7 +306,8 @@ bool FGFDMExec::Allocate(void)
 
   // Initialize planet (environment) constants
   LoadPlanetConstants();
-  GetGroundCallback()->SetSeaLevelRadius(Inertial->GetRefRadius());
+  //GetGroundCallback()->SetSeaLevelRadius(Inertial->GetRefRadius());
+  SetGroundCallback(new FGDefaultGroundCallback(Inertial->GetRefRadius()));
 
   // Initialize models
   for (unsigned int i = 0; i < Models.size(); i++) {
@@ -306,6 +319,7 @@ bool FGFDMExec::Allocate(void)
   }
 
   IC = new FGInitialCondition(this);
+  IC->bind(instance);
 
   modelLoaded = false;
 
@@ -362,10 +376,10 @@ bool FGFDMExec::Run(void)
   }
 
   if (ResetMode) {
-    if (ResetMode == 1) Output->SetStartNewOutput();
+    unsigned int mode = ResetMode;
 
     ResetMode = 0;
-    ResetToInitialConditions();
+    ResetToInitialConditions(mode);
   }
 
   if (Terminate) success = false;
@@ -591,16 +605,23 @@ bool FGFDMExec::RunIC(void)
 {
   FGPropulsion* propulsion = (FGPropulsion*)Models[ePropulsion];
 
-  if (!trim_status)
-    Models[eOutput]->InitModel();
+  Models[eOutput]->InitModel();
 
   SuspendIntegration(); // saves the integration rate, dt, then sets it to 0.0.
   Initialize(IC);
   Run();
   ResumeIntegration(); // Restores the integration rate to what it was.
 
-  for (unsigned int i=0; i<IC->GetNumEnginesRunning(); i++)
-    propulsion->InitRunning(IC->GetEngineRunning(i));
+  for (unsigned int n=0; n < propulsion->GetNumEngines(); ++n) {
+    if (IC->IsEngineRunning(n)) {
+      try {
+        propulsion->InitRunning(n);
+      } catch (string str) {
+        cerr << str << endl;
+        return false;
+      }
+    }
+  }
 
   return true;
 }
@@ -625,10 +646,12 @@ void FGFDMExec::Initialize(FGInitialCondition *FGIC)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGFDMExec::ResetToInitialConditions(void)
+void FGFDMExec::ResetToInitialConditions(int mode)
 {
   if (Constructing) return;
 
+  if (mode == 1) Output->SetStartNewOutput();
+
   for (unsigned int i = 0; i < Models.size(); i++) {
     // The Output model will be initialized during the RunIC() execution
     if (i == eOutput) continue;
@@ -898,7 +921,7 @@ bool FGFDMExec::LoadModel(const string& model, bool addModelToPath)
       Models[ePropulsion]->Run(false);  // Update propulsion properties for the report.
       LoadInputs(eMassBalance); // Update all (one more time) input mass properties for the report.
       Models[eMassBalance]->Run(false);  // Update all (one more time) mass properties for the report.
-      ((FGMassBalance*)Models[eMassBalance])->GetMassPropertiesReport();
+      ((FGMassBalance*)Models[eMassBalance])->GetMassPropertiesReport(0);
 
       cout << endl << fgblue << highint
            << "End of vehicle configuration loading." << endl
@@ -988,6 +1011,17 @@ void FGFDMExec::PrintPropertyCatalog(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGFDMExec::PrintSimulationConfiguration(void) const
+{
+  cout << endl << "Simulation Configuration" << endl << "------------------------" << endl;
+  cout << MassBalance->Name << endl;
+  cout << GroundReactions->Name << endl;
+  cout << Aerodynamics->Name << endl;
+  cout << Propulsion->Name << endl;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGFDMExec::ReadFileHeader(Element* el)
 {
   bool result = true; // true for success
@@ -1244,6 +1278,7 @@ void FGFDMExec::Debug(int from)
            << "JSBSim Flight Dynamics Model v" << JSBSim_version << endl;
       cout << "            [JSBSim-ML v" << needed_cfg_version << "]\n\n";
       cout << "JSBSim startup beginning ...\n\n";
+      if (disperse == 1) cout << "Dispersions are ON." << endl << endl;
     } else if (from == 3) {
       cout << "\n\nJSBSim startup complete\n\n";
     }
index 408abef1554b4b42c18e60f8a7cddfac693516cc..b3d7a7ba9e4723c40c81e7a436cbdd1e83ae02c1 100644 (file)
@@ -44,7 +44,6 @@ INCLUDES
 #include <vector>
 #include <string>
 
-#include "initialization/FGTrim.h"
 #include "FGJSBBase.h"
 #include "input_output/FGPropertyManager.h"
 #include "models/FGPropagate.h"
@@ -55,7 +54,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_FDMEXEC "$Id: FGFDMExec.h,v 1.86 2014/01/02 21:37:14 bcoconni Exp $"
+#define ID_FDMEXEC "$Id: FGFDMExec.h,v 1.91 2014/05/17 15:35:53 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -79,6 +78,7 @@ class FGInertial;
 class FGInput;
 class FGPropulsion;
 class FGMassBalance;
+class FGTrim;
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 CLASS DOCUMENTATION
@@ -178,7 +178,7 @@ CLASS DOCUMENTATION
                                 property actually maps toa function call of DoTrim().
 
     @author Jon S. Berndt
-    @version $Revision: 1.86 $
+    @version $Revision: 1.91 $
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -405,13 +405,7 @@ public:
 
   /// Returns the model name.
   const std::string& GetModelName(void) const { return modelName; }
-/*
-  /// Returns the current time.
-  double GetSimTime(void);
 
-  /// Returns the current frame time (delta T).
-  double GetDeltaT(void);
-*/  
   /// Returns a pointer to the property manager object.
   FGPropertyManager* GetPropertyManager(void);
   /// Returns a vector of strings representing the names of all loaded models (future)
@@ -448,6 +442,7 @@ public:
   void SetLoggingRate(double rate) { Output->SetRate(rate); }
 
   /** Sets (or overrides) the output filename
+      @param n index of file
       @param fname the name of the file to output data to
       @return true if successful, false if there is no output specified for the flight model */
   bool SetOutputFileName(const int n, const std::string& fname) { return Output->SetOutputName(n, fname); }
@@ -489,8 +484,12 @@ public:
   void Resume(void) {holding = false;}
   /// Returns true if the simulation is Holding (i.e. simulation time is not moving).
   bool Holding(void) {return holding;}
-  /// Resets the initial conditions object and prepares the simulation to run again.
-  void ResetToInitialConditions(void);
+  /** Resets the initial conditions object and prepares the simulation to run
+      again. If mode is set to 1 the output instances will take special actions
+      such as closing the current output file and open a new one with a
+      different name.
+      @param mode Sets the reset mode.*/
+  void ResetToInitialConditions(int mode);
   /// Sets the debug level.
   void SetDebugLevel(int level) {debug_lvl = level;}
 
@@ -518,6 +517,9 @@ public:
   // Print the contents of the property catalog for the loaded aircraft.
   void PrintPropertyCatalog(void);
 
+  // Print the simulation configuration
+  void PrintSimulationConfiguration(void) const;
+
   std::vector<std::string>& GetPropertyCatalog(void) {return PropertyCatalog;}
 
   void SetTrimStatus(bool status){ trim_status = status; }
@@ -583,6 +585,7 @@ private:
   int Error;
   unsigned int Frame;
   unsigned int IdFDM;
+  int disperse;
   unsigned short Terminate;
   double dT;
   double saved_dT;
@@ -647,6 +650,7 @@ private:
   void LoadModelConstants(void);
   bool Allocate(void);
   bool DeAllocate(void);
+  int GetDisperse(void) const {return disperse;}
 
   void Debug(int from);
 };
index 4df18d631a942fc6a64cfd60d943eda7bda95931..9149caa1641c9e972e004a5044514fcc4a88994f 100644 (file)
@@ -66,7 +66,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGInitialCondition.cpp,v 1.93 2014/01/13 10:46:00 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGInitialCondition.cpp,v 1.95 2014/05/01 18:32:54 bcoconni Exp $");
 IDENT(IdHdr,ID_INITIALCONDITION);
 
 //******************************************************************************
@@ -76,9 +76,7 @@ FGInitialCondition::FGInitialCondition(FGFDMExec *FDMExec) : fdmex(FDMExec)
   InitializeIC();
 
   if(FDMExec != NULL ) {
-    PropertyManager=fdmex->GetPropertyManager();
     Atmosphere=fdmex->GetAtmosphere();
-    bind();
   } else {
     cout << "FGInitialCondition: This class requires a pointer to a valid FGFDMExec object" << endl;
   }
@@ -152,7 +150,7 @@ void FGInitialCondition::InitializeIC(void)
 
   lastSpeedSet = setvt;
   lastAltitudeSet = setasl;
-  enginesRunning.clear();
+  enginesRunning = 0;
 }
 
 //******************************************************************************
@@ -907,7 +905,7 @@ bool FGInitialCondition::Load(string rstfile, bool useStoredPath)
   // Check to see if any engines are specified to be initialized in a running state
   Element* running_elements = document->FindElement("running");
   while (running_elements) {
-    enginesRunning.push_back(int(running_elements->GetDataAsNumber()));
+    enginesRunning &= 1 << int(running_elements->GetDataAsNumber());
     running_elements = document->FindNextElement("running");
   }
 
@@ -1257,7 +1255,7 @@ bool FGInitialCondition::Load_v2(Element* document)
 
 //******************************************************************************
 
-void FGInitialCondition::bind(void)
+void FGInitialCondition::bind(FGPropertyManager* PropertyManager)
 {
   PropertyManager->Tie("ic/vc-kts", this,
                        &FGInitialCondition::GetVcalibratedKtsIC,
index 57c9533060550c6a56b2837bbc2f174b20cdd385..273689e99f3f4788d2b524949eaa47253ffe52d8 100644 (file)
@@ -54,7 +54,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_INITIALCONDITION "$Id: FGInitialCondition.h,v 1.39 2013/11/24 11:40:55 bcoconni Exp $"
+#define ID_INITIALCONDITION "$Id: FGInitialCondition.h,v 1.41 2014/05/01 18:32:54 bcoconni Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -217,7 +217,7 @@ CLASS DOCUMENTATION
    @property ic/r-rad_sec (read/write) Yaw rate initial condition in radians/second
 
    @author Tony Peden
-   @version "$Id: FGInitialCondition.h,v 1.39 2013/11/24 11:40:55 bcoconni Exp $"
+   @version "$Id: FGInitialCondition.h,v 1.41 2014/05/01 18:32:54 bcoconni Exp $"
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -653,15 +653,12 @@ public:
       @return true if successful */
   bool Load(std::string rstname, bool useStoredPath = true );
 
-  /** Get the number of engines running
-   */
-  unsigned int GetNumEnginesRunning(void) const
-  { return (unsigned int)enginesRunning.size(); }
+  /** Is an engine running ?
+      @param index of the engine to be checked
+      @return true if the engine is running. */
+  bool IsEngineRunning(unsigned int n) const { return (enginesRunning & (1 << n)); }
 
-  /** Gets the running engine identification
-      @param engine index of running engine instance
-      @return the identification of running engine instance requested */
-  int GetEngineRunning(unsigned int engine) const { return enginesRunning[engine]; }
+  void bind(FGPropertyManager* pm);
 
 private:
   FGColumnVector3 vUVW_NED;
@@ -677,10 +674,9 @@ private:
 
   speedset lastSpeedSet;
   altitudeset lastAltitudeSet;
-  std::vector<int> enginesRunning;
+  unsigned int enginesRunning;
 
   FGFDMExec *fdmex;
-  FGPropertyManager *PropertyManager;
   FGAtmosphere* Atmosphere;
 
   bool Load_v1(Element* document);
@@ -695,7 +691,6 @@ private:
   double GetBodyVelFpsIC(int idx) const;
   void calcAeroAngles(const FGColumnVector3& _vt_BODY);
   void calcThetaBeta(double alfa, const FGColumnVector3& _vt_NED);
-  void bind(void);
   void Debug(int from);
 };
 }
index c5d9caa8706d0c33a4cd12bd4e734a5d914216f3..9438f795f66c78ebd090ce0a18d807d2dc9e6e02 100644 (file)
@@ -16,6 +16,7 @@
  * with this program.  If not, see <http://www.gnu.org/licenses/>.
  */
 
+#include "FGInitialCondition.h"
 #include "FGLinearization.h"
 #include <ctime>
 
old mode 100755 (executable)
new mode 100644 (file)
index 1f8a196..e1bec05
@@ -16,6 +16,7 @@
  * with this program.  If not, see <http://www.gnu.org/licenses/>.
  */
 
+#include "FGTrim.h"
 #include "FGSimplexTrim.h"
 #include <ctime>
 
index d4b1112e3e5edb93d7fd228f846790bc2be1f2d6..3de32e76e8fdaab50361843afe46eb778d149831 100644 (file)
@@ -57,14 +57,16 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGTrim.cpp,v 1.22 2014/01/13 10:46:00 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGTrim.cpp,v 1.23 2014/05/01 18:32:54 bcoconni Exp $");
 IDENT(IdHdr,ID_TRIM);
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-FGTrim::FGTrim(FGFDMExec *FDMExec,TrimMode tt) {
+FGTrim::FGTrim(FGFDMExec *FDMExec,TrimMode tt)
+  : fgic(FDMExec)
+{
 
-  N=Nsub=0;
+  Nsub=0;
   max_iterations=60;
   max_sub_iterations=100;
   Tolerance=1E-3;
@@ -72,11 +74,8 @@ FGTrim::FGTrim(FGFDMExec *FDMExec,TrimMode tt) {
 
   Debug=0;DebugLevel=0;
   fdmex=FDMExec;
-  fgic=fdmex->GetIC();
   total_its=0;
-  trimudot=true;
   gamma_fallback=false;
-  axis_count=0;
   mode=tt;
   xlo=xhi=alo=ahi=0.0;
   targetNlf=1.0;
@@ -88,12 +87,6 @@ FGTrim::FGTrim(FGFDMExec *FDMExec,TrimMode tt) {
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 FGTrim::~FGTrim(void) {
-  for(current_axis=0; current_axis<TrimAxes.size(); current_axis++) {
-    delete TrimAxes[current_axis];
-  }
-  delete[] sub_iterations;
-  delete[] successful;
-  delete[] solution;
   if (debug_lvl & 2) cout << "Destroyed:    FGTrim" << endl;
 }
 
@@ -105,13 +98,13 @@ void FGTrim::TrimStats() {
   cout << "    Total Iterations: " << total_its << endl;
   if( total_its > 0) {
     cout << "    Sub-iterations:" << endl;
-    for (current_axis=0; current_axis<TrimAxes.size(); current_axis++) {
-      run_sum += TrimAxes[current_axis]->GetRunCount();
-      cout << "   " << setw(5) << TrimAxes[current_axis]->GetStateName().c_str()
+    for (unsigned int current_axis=0; current_axis<TrimAxes.size(); current_axis++) {
+      run_sum += TrimAxes[current_axis].GetRunCount();
+      cout << "   " << setw(5) << TrimAxes[current_axis].GetStateName().c_str()
            << ": " << setprecision(3) << sub_iterations[current_axis]
            << " average: " << setprecision(5) << sub_iterations[current_axis]/double(total_its)
            << "  successful:  " << setprecision(3) << successful[current_axis]
-           << "  stability: " << setprecision(5) << TrimAxes[current_axis]->GetAvgStability()
+           << "  stability: " << setprecision(5) << TrimAxes[current_axis].GetAvgStability()
            << endl;
     }
     cout << "    Run Count: " << run_sum << endl;
@@ -122,24 +115,15 @@ void FGTrim::TrimStats() {
 
 void FGTrim::Report(void) {
   cout << "  Trim Results: " << endl;
-  for(current_axis=0; current_axis<TrimAxes.size(); current_axis++)
-    TrimAxes[current_axis]->AxisReport();
+  for(unsigned int current_axis=0; current_axis<TrimAxes.size(); current_axis++)
+    TrimAxes[current_axis].AxisReport();
 
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 void FGTrim::ClearStates(void) {
-    FGTrimAxis* ta;
-
     mode=tCustom;
-    vector<FGTrimAxis*>::iterator iAxes;
-    iAxes = TrimAxes.begin();
-    while (iAxes != TrimAxes.end()) {
-      ta=*iAxes;
-      delete ta;
-      iAxes++;
-    }
     TrimAxes.clear();
     //cout << "TrimAxes.size(): " << TrimAxes.size() << endl;
 }
@@ -147,54 +131,40 @@ void FGTrim::ClearStates(void) {
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 bool FGTrim::AddState( State state, Control control ) {
-  FGTrimAxis* ta;
-  bool result=true;
-
   mode = tCustom;
-  vector <FGTrimAxis*>::iterator iAxes = TrimAxes.begin();
-  while (iAxes != TrimAxes.end()) {
-      ta=*iAxes;
-      if( ta->GetStateType() == state )
-        result=false;
-      iAxes++;
+  vector <FGTrimAxis>::iterator iAxes = TrimAxes.begin();
+  for (; iAxes != TrimAxes.end(); ++iAxes) {
+    if (iAxes->GetStateType() == state)
+      return false;
   }
-  if(result) {
-    TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,state,control));
-    delete[] sub_iterations;
-    delete[] successful;
-    delete[] solution;
-    sub_iterations=new double[TrimAxes.size()];
-    successful=new double[TrimAxes.size()];
-    solution=new bool[TrimAxes.size()];
-  }
-  return result;
+
+  TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,state,control));
+  sub_iterations.resize(TrimAxes.size());
+  successful.resize(TrimAxes.size());
+  solution.resize(TrimAxes.size());
+
+  return true;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 bool FGTrim::RemoveState( State state ) {
-  FGTrimAxis* ta;
   bool result=false;
 
   mode = tCustom;
-  vector <FGTrimAxis*>::iterator iAxes = TrimAxes.begin();
+  vector <FGTrimAxis>::iterator iAxes = TrimAxes.begin();
   while (iAxes != TrimAxes.end()) {
-      ta=*iAxes;
-      if( ta->GetStateType() == state ) {
-        delete ta;
+      if( iAxes->GetStateType() == state ) {
         iAxes = TrimAxes.erase(iAxes);
         result=true;
         continue;
       }
-      iAxes++;
+      ++iAxes;
   }
   if(result) {
-    delete[] sub_iterations;
-    delete[] successful;
-    delete[] solution;
-    sub_iterations=new double[TrimAxes.size()];
-    successful=new double[TrimAxes.size()];
-    solution=new bool[TrimAxes.size()];
+    sub_iterations.resize(TrimAxes.size());
+    successful.resize(TrimAxes.size());
+    solution.resize(TrimAxes.size());
   }
   return result;
 }
@@ -202,74 +172,65 @@ bool FGTrim::RemoveState( State state ) {
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 bool FGTrim::EditState( State state, Control new_control ){
-  FGTrimAxis* ta;
-  bool result=false;
-
   mode = tCustom;
-  vector <FGTrimAxis*>::iterator iAxes = TrimAxes.begin();
+  vector <FGTrimAxis>::iterator iAxes = TrimAxes.begin();
   while (iAxes != TrimAxes.end()) {
-      ta=*iAxes;
-      if( ta->GetStateType() == state ) {
-        TrimAxes.insert(iAxes,1,new FGTrimAxis(fdmex,fgic,state,new_control));
-        delete ta;
-        TrimAxes.erase(iAxes+1);
-        result=true;
-        break;
+      if( iAxes->GetStateType() == state ) {
+        *iAxes = FGTrimAxis(fdmex,&fgic,state,new_control);
+        return true;
       }
-      iAxes++;
+      ++iAxes;
   }
-  return result;
+  return false;
 }
 
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 bool FGTrim::DoTrim(void) {
-
-  trim_failed=false;
-  int i;
+  bool trim_failed=false;
+  unsigned int N = 0;
+  unsigned int axis_count = 0;
   FGFCS *FCS = fdmex->GetFCS();
   vector<double> throttle0 = FCS->GetThrottleCmd();
   double elevator0 = FCS->GetDeCmd();
   double aileron0 = FCS->GetDaCmd();
   double rudder0 = FCS->GetDrCmd();
   double PitchTrim0 = FCS->GetPitchTrimCmd();
-  FGInitialCondition fgic0 = *fgic;
+  fgic = *fdmex->GetIC();
 
-  for(i=0;i < fdmex->GetGroundReactions()->GetNumGearUnits();i++){
+  for(int i=0;i < fdmex->GetGroundReactions()->GetNumGearUnits();i++){
     fdmex->GetGroundReactions()->GetGearUnit(i)->SetReport(false);
   }
 
   fdmex->DisableOutput();
 
   fdmex->SetTrimStatus(true);
-  fdmex->RunIC();
   fdmex->SuspendIntegration();
 
-  fgic->SetPRadpsIC(0.0);
-  fgic->SetQRadpsIC(0.0);
-  fgic->SetRRadpsIC(0.0);
+  fgic.SetPRadpsIC(0.0);
+  fgic.SetQRadpsIC(0.0);
+  fgic.SetRRadpsIC(0.0);
 
   if (mode == tGround) {
     trimOnGround();
-    double theta = fgic->GetThetaRadIC();
-    double phi = fgic->GetPhiRadIC();
+    double theta = fgic.GetThetaRadIC();
+    double phi = fgic.GetPhiRadIC();
     // Take opportunity of the first approx. found by trimOnGround() to
     // refine the control limits.
-    TrimAxes[0]->SetControlLimits(0., fgic->GetAltitudeAGLFtIC());
-    TrimAxes[1]->SetControlLimits(theta - 5.0 * degtorad, theta + 5.0 * degtorad);
-    TrimAxes[2]->SetControlLimits(phi - 30.0 * degtorad, phi + 30.0 * degtorad);
+    TrimAxes[0].SetControlLimits(0., fgic.GetAltitudeAGLFtIC());
+    TrimAxes[1].SetControlLimits(theta - 5.0 * degtorad, theta + 5.0 * degtorad);
+    TrimAxes[2].SetControlLimits(phi - 30.0 * degtorad, phi + 30.0 * degtorad);
   }
 
   //clear the sub iterations counts & zero out the controls
-  for(current_axis=0;current_axis<TrimAxes.size();current_axis++) {
+  for(unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
     //cout << current_axis << "  " << TrimAxes[current_axis]->GetStateName()
     //<< "  " << TrimAxes[current_axis]->GetControlName()<< endl;
-    xlo=TrimAxes[current_axis]->GetControlMin();
-    xhi=TrimAxes[current_axis]->GetControlMax();
-    TrimAxes[current_axis]->SetControl((xlo+xhi)/2);
-    TrimAxes[current_axis]->Run();
-    //TrimAxes[current_axis]->AxisReport();
+    xlo=TrimAxes[current_axis].GetControlMin();
+    xhi=TrimAxes[current_axis].GetControlMax();
+    TrimAxes[current_axis].SetControl((xlo+xhi)/2);
+    TrimAxes[current_axis].Run();
+    //TrimAxes[current_axis].AxisReport();
     sub_iterations[current_axis]=0;
     successful[current_axis]=0;
     solution[current_axis]=false;
@@ -279,35 +240,35 @@ bool FGTrim::DoTrim(void) {
     cout << "Setting pitch rate and nlf... " << endl;
     setupPullup();
     cout << "pitch rate done ... " << endl;
-    TrimAxes[0]->SetStateTarget(targetNlf);
+    TrimAxes[0].SetStateTarget(targetNlf);
     cout << "nlf done" << endl;
   } else if (mode == tTurn) {
     setupTurn();
-    //TrimAxes[0]->SetStateTarget(targetNlf);
+    //TrimAxes[0].SetStateTarget(targetNlf);
   }
 
   do {
     axis_count=0;
-    for(current_axis=0;current_axis<TrimAxes.size();current_axis++) {
-      setDebug();
+    for(unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
+      setDebug(TrimAxes[current_axis]);
       updateRates();
       Nsub=0;
       if(!solution[current_axis]) {
-        if(checkLimits()) {
+        if(checkLimits(TrimAxes[current_axis])) {
           solution[current_axis]=true;
-          solve();
+          solve(TrimAxes[current_axis]);
         }
-      } else if(findInterval()) {
-        solve();
+      } else if(findInterval(TrimAxes[current_axis])) {
+        solve(TrimAxes[current_axis]);
       } else {
         solution[current_axis]=false;
       }
       sub_iterations[current_axis]+=Nsub;
     }
-    for(current_axis=0;current_axis<TrimAxes.size();current_axis++) {
+    for(unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
       //these checks need to be done after all the axes have run
-      if(Debug > 0) TrimAxes[current_axis]->AxisReport();
-      if(TrimAxes[current_axis]->InTolerance()) {
+      if(Debug > 0) TrimAxes[current_axis].AxisReport();
+      if(TrimAxes[current_axis].InTolerance()) {
         axis_count++;
         successful[current_axis]++;
       }
@@ -320,27 +281,25 @@ bool FGTrim::DoTrim(void) {
       //is, keep going until success or max iteration count
 
       //Oh, well: two out of three ain't bad
-      for(current_axis=0;current_axis<TrimAxes.size();current_axis++) {
+      for(unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
         //these checks need to be done after all the axes have run
-        if(!TrimAxes[current_axis]->InTolerance()) {
-          if(!checkLimits()) {
+        if(!TrimAxes[current_axis].InTolerance()) {
+          if(!checkLimits(TrimAxes[current_axis])) {
             // special case this for now -- if other cases arise proper
             // support can be added to FGTrimAxis
             if( (gamma_fallback) &&
-                (TrimAxes[current_axis]->GetStateType() == tUdot) &&
-                (TrimAxes[current_axis]->GetControlType() == tThrottle)) {
+                (TrimAxes[current_axis].GetStateType() == tUdot) &&
+                (TrimAxes[current_axis].GetControlType() == tThrottle)) {
               cout << "  Can't trim udot with throttle, trying flight"
               << " path angle. (" << N << ")" << endl;
-              if(TrimAxes[current_axis]->GetState() > 0)
-                TrimAxes[current_axis]->SetControlToMin();
+              if(TrimAxes[current_axis].GetState() > 0)
+                TrimAxes[current_axis].SetControlToMin();
               else
-                TrimAxes[current_axis]->SetControlToMax();
-              TrimAxes[current_axis]->Run();
-              delete TrimAxes[current_axis];
-              TrimAxes[current_axis]=new FGTrimAxis(fdmex,fgic,tUdot,
-                                                    tGamma );
+                TrimAxes[current_axis].SetControlToMax();
+              TrimAxes[current_axis].Run();
+              TrimAxes[current_axis]=FGTrimAxis(fdmex,&fgic,tUdot,tGamma);
             } else {
-              cout << "  Sorry, " << TrimAxes[current_axis]->GetStateName()
+              cout << "  Sorry, " << TrimAxes[current_axis].GetStateName()
               << " doesn't appear to be trimmable" << endl;
               //total_its=k;
               trim_failed=true; //force the trim to fail
@@ -362,7 +321,7 @@ bool FGTrim::DoTrim(void) {
     total_its=N;
 
     // Restore the aircraft parameters to their initial values
-    *fgic = fgic0;
+    fgic = *fdmex->GetIC();
     FCS->SetDeCmd(elevator0);
     FCS->SetDaCmd(aileron0);
     FCS->SetDrCmd(rudder0);
@@ -370,23 +329,22 @@ bool FGTrim::DoTrim(void) {
     for (unsigned int i=0; i < throttle0.size(); i++)
       FCS->SetThrottleCmd(i, throttle0[i]);
 
+    fdmex->Initialize(&fgic);
+    fdmex->Run();
+
     // If WOW is true we must make sure there are no gears into the ground.
-    if (fdmex->GetGroundReactions()->GetWOW()) {
-      fdmex->Initialize(fgic);
-      fdmex->Run();
+    if (fdmex->GetGroundReactions()->GetWOW())
       trimOnGround();
-    }
 
     if (debug_lvl > 0)
         cout << endl << "  Trim failed" << endl;
   }
 
   fdmex->ResumeIntegration();
-  fdmex->RunIC();
   fdmex->SetTrimStatus(false);
   fdmex->EnableOutput();
 
-  for(i=0;i < fdmex->GetGroundReactions()->GetNumGearUnits();i++){
+  for(int i=0;i < fdmex->GetGroundReactions()->GetNumGearUnits();i++){
     fdmex->GetGroundReactions()->GetGearUnit(i)->SetReport(true);
   }
 
@@ -462,8 +420,8 @@ void FGTrim::trimOnGround(void)
 
   // Update the initial conditions: this should remove the forces generated
   // by overcompressed landing gears
-  fgic->SetAltitudeASLFtIC(fgic->GetAltitudeASLFtIC() - hmin);
-  fdmex->Initialize(fgic);
+  fgic.SetAltitudeASLFtIC(fgic.GetAltitudeASLFtIC() - hmin);
+  fdmex->Initialize(&fgic);
   fdmex->Run();
 
   // Compute the rotation axis: it is obtained from the direction of the
@@ -505,11 +463,11 @@ void FGTrim::trimOnGround(void)
   FGQuaternion q1(rParam.angleMin, rotationAxis);
 
   // Update the aircraft orientation
-  FGColumnVector3 euler = (q0 * q1 * fgic->GetOrientation()).GetEuler();
+  FGColumnVector3 euler = (q0 * q1 * fgic.GetOrientation()).GetEuler();
 
-  fgic->SetPhiRadIC(euler(1));
-  fgic->SetThetaRadIC(euler(2));
-  fgic->SetPsiRadIC(euler(3));
+  fgic.SetPhiRadIC(euler(1));
+  fgic.SetThetaRadIC(euler(2));
+  fgic.SetPsiRadIC(euler(3));
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -569,11 +527,11 @@ FGTrim::RotationParameters FGTrim::calcRotation(vector<ContactPoints>& contacts,
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-bool FGTrim::solve(void) {
+bool FGTrim::solve(FGTrimAxis& axis) {
 
   double x1,x2,x3,f1,f2,f3,d,d0;
   const double relax =0.9;
-  double eps=TrimAxes[current_axis]->GetSolverEps();
+  double eps=axis.GetSolverEps();
 
   x1=x2=x3=0;
   d=1;
@@ -589,15 +547,15 @@ bool FGTrim::solve(void) {
     }   */
     d0=fabs(x3-x1);
     //iterations
-    //max_sub_iterations=TrimAxes[current_axis]->GetIterationLimit();
-    while ( (TrimAxes[current_axis]->InTolerance() == false )
+    //max_sub_iterations=axis.GetIterationLimit();
+    while ( (axis.InTolerance() == false )
              && (fabs(d) > eps) && (Nsub < max_sub_iterations)) {
       Nsub++;
       d=(x3-x1)/d0;
       x2=x1-d*d0*f1/(f3-f1);
-      TrimAxes[current_axis]->SetControl(x2);
-      TrimAxes[current_axis]->Run();
-      f2=TrimAxes[current_axis]->GetState();
+      axis.SetControl(x2);
+      axis.Run();
+      f2=axis.GetState();
       if(Debug > 1) {
         cout << "FGTrim::solve Nsub,x1,x2,x3: " << Nsub << ", " << x1
         << ", " << x2 << ", " << x3 << endl;
@@ -650,13 +608,13 @@ bool FGTrim::solve(void) {
  no assumptions about the state of the sim after this function has run
  can be made.
 */
-bool FGTrim::findInterval(void) {
+bool FGTrim::findInterval(FGTrimAxis& axis) {
   bool found=false;
   double step;
-  double current_control=TrimAxes[current_axis]->GetControl();
-  double current_accel=TrimAxes[current_axis]->GetState();;
-  double xmin=TrimAxes[current_axis]->GetControlMin();
-  double xmax=TrimAxes[current_axis]->GetControlMax();
+  double current_control=axis.GetControl();
+  double current_accel=axis.GetState();;
+  double xmin=axis.GetControlMin();
+  double xmax=axis.GetControlMax();
   double lastxlo,lastxhi,lastalo,lastahi;
 
   step=0.025*fabs(xmax);
@@ -672,13 +630,13 @@ bool FGTrim::findInterval(void) {
     if(xlo < xmin) xlo=xmin;
     xhi+=step;
     if(xhi > xmax) xhi=xmax;
-    TrimAxes[current_axis]->SetControl(xlo);
-    TrimAxes[current_axis]->Run();
-    alo=TrimAxes[current_axis]->GetState();
-    TrimAxes[current_axis]->SetControl(xhi);
-    TrimAxes[current_axis]->Run();
-    ahi=TrimAxes[current_axis]->GetState();
-    if(fabs(ahi-alo) <= TrimAxes[current_axis]->GetTolerance()) continue;
+    axis.SetControl(xlo);
+    axis.Run();
+    alo=axis.GetState();
+    axis.SetControl(xhi);
+    axis.Run();
+    ahi=axis.GetState();
+    if(fabs(ahi-alo) <= axis.GetTolerance()) continue;
     if(alo*ahi <=0) {  //found interval with root
       found=true;
       if(alo*current_accel <= 0) { //narrow interval down a bit
@@ -720,25 +678,26 @@ bool FGTrim::findInterval(void) {
 //xhi=xmax and ahi=accel(xmax)
 //in all cases the sim is left such that the control=xmax and accel=ahi
 
-bool FGTrim::checkLimits(void) {
+bool FGTrim::checkLimits(FGTrimAxis& axis)
+{
   bool solutionExists;
-  double current_control=TrimAxes[current_axis]->GetControl();
-  double current_accel=TrimAxes[current_axis]->GetState();
-  xlo=TrimAxes[current_axis]->GetControlMin();
-  xhi=TrimAxes[current_axis]->GetControlMax();
-
-  TrimAxes[current_axis]->SetControl(xlo);
-  TrimAxes[current_axis]->Run();
-  alo=TrimAxes[current_axis]->GetState();
-  TrimAxes[current_axis]->SetControl(xhi);
-  TrimAxes[current_axis]->Run();
-  ahi=TrimAxes[current_axis]->GetState();
+  double current_control=axis.GetControl();
+  double current_accel=axis.GetState();
+  xlo=axis.GetControlMin();
+  xhi=axis.GetControlMax();
+
+  axis.SetControl(xlo);
+  axis.Run();
+  alo=axis.GetState();
+  axis.SetControl(xhi);
+  axis.Run();
+  ahi=axis.GetState();
   if(Debug > 1)
     cout << "checkLimits() xlo,xhi,alo,ahi: " << xlo << ", " << xhi << ", "
                                               << alo << ", " << ahi << endl;
   solutionDomain=0;
   solutionExists=false;
-  if(fabs(ahi-alo) > TrimAxes[current_axis]->GetTolerance()) {
+  if(fabs(ahi-alo) > axis.GetTolerance()) {
     if(alo*current_accel <= 0) {
       solutionExists=true;
       solutionDomain=-1;
@@ -751,8 +710,8 @@ bool FGTrim::checkLimits(void) {
       alo=current_accel;
     }
   }
-  TrimAxes[current_axis]->SetControl(current_control);
-  TrimAxes[current_axis]->Run();
+  axis.SetControl(current_control);
+  axis.Run();
   return solutionExists;
 }
 
@@ -761,12 +720,12 @@ bool FGTrim::checkLimits(void) {
 void FGTrim::setupPullup() {
   double g,q,cgamma;
   g=fdmex->GetInertial()->gravity();
-  cgamma=cos(fgic->GetFlightPathAngleRadIC());
+  cgamma=cos(fgic.GetFlightPathAngleRadIC());
   cout << "setPitchRateInPullup():  " << g << ", " << cgamma << ", "
-       << fgic->GetVtrueFpsIC() << endl;
-  q=g*(targetNlf-cgamma)/fgic->GetVtrueFpsIC();
+       << fgic.GetVtrueFpsIC() << endl;
+  q=g*(targetNlf-cgamma)/fgic.GetVtrueFpsIC();
   cout << targetNlf << ", " << q << endl;
-  fgic->SetQRadpsIC(q);
+  fgic.SetQRadpsIC(q);
   cout << "setPitchRateInPullup() complete" << endl;
 
 }
@@ -775,11 +734,11 @@ void FGTrim::setupPullup() {
 
 void FGTrim::setupTurn(void){
   double g,phi;
-  phi = fgic->GetPhiRadIC();
+  phi = fgic.GetPhiRadIC();
   if( fabs(phi) > 0.001 && fabs(phi) < 1.56 ) {
     targetNlf = 1 / cos(phi);
     g = fdmex->GetInertial()->gravity();
-    psidot = g*tan(phi) / fgic->GetUBodyFpsIC();
+    psidot = g*tan(phi) / fgic.GetUBodyFpsIC();
     cout << targetNlf << ", " << psidot << endl;
   }
 
@@ -789,36 +748,36 @@ void FGTrim::setupTurn(void){
 
 void FGTrim::updateRates(void){
   if( mode == tTurn ) {
-    double phi = fgic->GetPhiRadIC();
+    double phi = fgic.GetPhiRadIC();
     double g = fdmex->GetInertial()->gravity();
     double p,q,r,theta;
     if(fabs(phi) > 0.001 && fabs(phi) < 1.56 ) {
-      theta=fgic->GetThetaRadIC();
-      phi=fgic->GetPhiRadIC();
-      psidot = g*tan(phi) / fgic->GetUBodyFpsIC();
+      theta=fgic.GetThetaRadIC();
+      phi=fgic.GetPhiRadIC();
+      psidot = g*tan(phi) / fgic.GetUBodyFpsIC();
       p=-psidot*sin(theta);
       q=psidot*cos(theta)*sin(phi);
       r=psidot*cos(theta)*cos(phi);
     } else {
       p=q=r=0;
     }
-    fgic->SetPRadpsIC(p);
-    fgic->SetQRadpsIC(q);
-    fgic->SetRRadpsIC(r);
+    fgic.SetPRadpsIC(p);
+    fgic.SetQRadpsIC(q);
+    fgic.SetRRadpsIC(r);
   } else if( mode == tPullup && fabs(targetNlf-1) > 0.01) {
       double g,q,cgamma;
       g=fdmex->GetInertial()->gravity();
-      cgamma=cos(fgic->GetFlightPathAngleRadIC());
-      q=g*(targetNlf-cgamma)/fgic->GetVtrueFpsIC();
-      fgic->SetQRadpsIC(q);
+      cgamma=cos(fgic.GetFlightPathAngleRadIC());
+      q=g*(targetNlf-cgamma)/fgic.GetVtrueFpsIC();
+      fgic.SetQRadpsIC(q);
   }
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGTrim::setDebug(void) {
+void FGTrim::setDebug(FGTrimAxis& axis) {
   if(debug_axis == tAll ||
-      TrimAxes[current_axis]->GetStateType() == debug_axis ) {
+      axis.GetStateType() == debug_axis ) {
     Debug=DebugLevel;
     return;
   } else {
@@ -836,54 +795,53 @@ void FGTrim::SetMode(TrimMode tt) {
       case tFull:
         if (debug_lvl > 0)
           cout << "  Full Trim" << endl;
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tWdot,tAlpha ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tUdot,tThrottle ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tQdot,tPitchTrim ));
-        //TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tHmgt,tBeta ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tVdot,tPhi ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tPdot,tAileron ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tRdot,tRudder ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tWdot,tAlpha));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
+        //TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tHmgt,tBeta ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tVdot,tPhi ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tPdot,tAileron ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tRdot,tRudder ));
         break;
       case tLongitudinal:
         if (debug_lvl > 0)
           cout << "  Longitudinal Trim" << endl;
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tWdot,tAlpha ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tUdot,tThrottle ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tQdot,tPitchTrim ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tWdot,tAlpha ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
         break;
       case tGround:
         if (debug_lvl > 0)
           cout << "  Ground Trim" << endl;
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tWdot,tAltAGL ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tQdot,tTheta ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tPdot,tPhi ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tWdot,tAltAGL ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tQdot,tTheta ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tPdot,tPhi ));
         break;
       case tPullup:
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tNlf,tAlpha ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tUdot,tThrottle ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tQdot,tPitchTrim ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tHmgt,tBeta ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tVdot,tPhi ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tPdot,tAileron ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tRdot,tRudder ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tNlf,tAlpha ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tHmgt,tBeta ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tVdot,tPhi ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tPdot,tAileron ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tRdot,tRudder ));
         break;
       case tTurn:
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tWdot,tAlpha ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tUdot,tThrottle ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tQdot,tPitchTrim ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tVdot,tBeta ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tPdot,tAileron ));
-        TrimAxes.push_back(new FGTrimAxis(fdmex,fgic,tRdot,tRudder ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tWdot,tAlpha ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tVdot,tBeta ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tPdot,tAileron ));
+        TrimAxes.push_back(FGTrimAxis(fdmex,&fgic,tRdot,tRudder ));
         break;
       case tCustom:
       case tNone:
         break;
     }
     //cout << "TrimAxes.size(): " << TrimAxes.size() << endl;
-    sub_iterations=new double[TrimAxes.size()];
-    successful=new double[TrimAxes.size()];
-    solution=new bool[TrimAxes.size()];
-    current_axis=0;
+    sub_iterations.resize(TrimAxes.size());
+    successful.resize(TrimAxes.size());
+    solution.resize(TrimAxes.size());
 }
 //YOU WERE WARNED, BUT YOU DID IT ANYWAY.
 }
index 4ad5e056f2e9eb4a3261815e686672c9f602a65d..5c8b76401b1365272d6a37bdc4e58e5c00956f12 100644 (file)
@@ -60,7 +60,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_TRIM "$Id: FGTrim.h,v 1.10 2013/11/24 16:53:15 bcoconni Exp $"
+#define ID_TRIM "$Id: FGTrim.h,v 1.11 2014/05/01 18:32:54 bcoconni Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -120,7 +120,7 @@ CLASS DOCUMENTATION
     @endcode
     
     @author Tony Peden
-    @version "$Id: FGTrim.h,v 1.10 2013/11/24 16:53:15 bcoconni Exp $"
+    @version "$Id: FGTrim.h,v 1.11 2014/05/01 18:32:54 bcoconni Exp $"
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -131,35 +131,28 @@ class FGTrim : public FGJSBBase
 {
 private:
 
-  std::vector<FGTrimAxis*> TrimAxes;
-  unsigned int current_axis;
-  int N, Nsub;
+  std::vector<FGTrimAxis> TrimAxes;
+  unsigned int Nsub;
   TrimMode mode;
   int DebugLevel, Debug;
   double Tolerance, A_Tolerance;
-  double wdot,udot,qdot;
-  double dth;
-  double *sub_iterations;
-  double *successful;
-  bool *solution;
-  int max_sub_iterations;
-  int max_iterations;
-  int total_its;
-  bool trimudot;
+  std::vector<double> sub_iterations, successful;
+  std::vector<bool> solution;
+  unsigned int max_sub_iterations;
+  unsigned int max_iterations;
+  unsigned int total_its;
   bool gamma_fallback;
-  bool trim_failed;
-  unsigned int axis_count;
   int solutionDomain;
   double xlo,xhi,alo,ahi;
   double targetNlf;
   int debug_axis;
 
-  double psidot,thetadot;
+  double psidot;
 
   FGFDMExec* fdmex;
-  FGInitialCondition* fgic;
+  FGInitialCondition fgic;
 
-  bool solve(void);
+  bool solve(FGTrimAxis& axis);
 
   /** @return false if there is no change in the current axis accel
       between accel(control_min) and accel(control_max). If there is a
@@ -168,15 +161,15 @@ private:
      -1 if sign change between accel(control_min) and accel(0)
       1 if sign between accel(0) and accel(control_max)
   */
-  bool findInterval(void);
+  bool findInterval(FGTrimAxis& axis);
 
-  bool checkLimits(void);
+  bool checkLimits(FGTrimAxis& axis);
 
   void setupPullup(void);
   void setupTurn(void);
 
   void updateRates(void);
-  void setDebug(void);
+  void setDebug(FGTrimAxis& axis);
 
   struct ContactPoints {
     FGColumnVector3 location;
old mode 100755 (executable)
new mode 100644 (file)
index f64326c..7ec259a
@@ -30,6 +30,7 @@
 #include <cstdlib>
 #include <stdexcept>
 #include "simgear/misc/stdint.hxx"
+#include "FGInitialCondition.h"
 
 namespace JSBSim
 {
index 7af9ee787dc0933598cf20fd5f39faca80a63c78..96ddde811baddecc61b152e9ce8e617ee712ef56 100644 (file)
@@ -45,7 +45,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_GROUNDCALLBACK "$Id: FGGroundCallback.h,v 1.16 2013/02/02 13:23:40 bcoconni Exp $"
+#define ID_GROUNDCALLBACK "$Id: FGGroundCallback.h,v 1.17 2014/05/17 15:35:54 jberndt Exp $"
 
 namespace JSBSim {
 
@@ -62,7 +62,7 @@ CLASS DOCUMENTATION
     ball formed earth with an adjustable terrain elevation.
 
     @author Mathias Froehlich
-    @version $Id: FGGroundCallback.h,v 1.16 2013/02/02 13:23:40 bcoconni Exp $
+    @version $Id: FGGroundCallback.h,v 1.17 2014/05/17 15:35:54 jberndt Exp $
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -132,7 +132,8 @@ class FGDefaultGroundCallback : public FGGroundCallback
 {
 public:
 
-   FGDefaultGroundCallback(double referenceRadius = 20925650.0);
+   // This should not be hardcoded, but retrieved from FGInertial
+   FGDefaultGroundCallback(double referenceRadius);
 
    double GetAltitude(const FGLocation& l) const;
 
index 99c98dca39f00d846c95b7535f6749387e650b3b..52e0e5e7dabd2ef4f0cb41aa2d1e0ff164bccea9 100644 (file)
@@ -71,7 +71,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGOutputFG.cpp,v 1.8 2014/01/13 10:46:00 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGOutputFG.cpp,v 1.9 2014/02/17 05:01:55 jberndt Exp $");
 IDENT(IdHdr,ID_OUTPUTFG);
 
 // (stolen from FGFS native_fdm.cxx)
@@ -137,8 +137,8 @@ void FGOutputFG::SocketDataFill(FGNetFDM* net)
   net->version = FG_NET_FDM_VERSION;
 
   // Positions
-  net->longitude = Propagate->GetLocation().GetLongitude(); // geodetic (radians)
-  net->latitude  = Propagate->GetLocation().GetLatitude(); // geodetic (radians)
+  net->longitude = Propagate->GetLocation().GetLongitude(); // 
+  net->latitude  = Propagate->GetLocation().GetGeodLatitudeRad(); // geodetic (radians)
   net->altitude  = Propagate->GetAltitudeASL()*0.3048; // altitude, above sea level (meters)
   net->agl       = (float)(Propagate->GetDistanceAGL()*0.3048); // altitude, above ground level (meters)
 
index 431c2ebe0fe0c3979f7ff3c0a6981729fad365c9..6e1024037162c43b9cd32fd8c70699471e11f738 100644 (file)
@@ -47,7 +47,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGOutputFile.cpp,v 1.6 2014/01/13 10:46:00 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGOutputFile.cpp,v 1.9 2014/05/04 17:00:27 bcoconni Exp $");
 IDENT(IdHdr,ID_OUTPUTFILE);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -56,7 +56,7 @@ CLASS IMPLEMENTATION
 
 FGOutputFile::FGOutputFile(FGFDMExec* fdmex) :
   FGOutputType(fdmex),
-  runID_postfix(0)
+  runID_postfix(-1)
 {
 }
 
@@ -64,8 +64,13 @@ FGOutputFile::FGOutputFile(FGFDMExec* fdmex) :
 
 bool FGOutputFile::InitModel(void)
 {
-  if (FGOutputType::InitModel())
+  if (FGOutputType::InitModel()) {
+    if (Filename.empty()) {
+      Filename = Name;
+      runID_postfix = 0;
+    }
     return OpenFile();
+  }
 
   return false;
 }
@@ -74,7 +79,7 @@ bool FGOutputFile::InitModel(void)
 
 void FGOutputFile::SetStartNewOutput(void)
 {
-  if (Filename.size() > 0) {
+  if (runID_postfix >= 0) {
     ostringstream buf;
     string::size_type dot = Name.find_last_of('.');
     if (dot != string::npos) {
@@ -83,8 +88,9 @@ void FGOutputFile::SetStartNewOutput(void)
       buf << Name << '_' << runID_postfix++;
     }
     Filename = buf.str();
-    CloseFile();
   }
+
+  CloseFile();
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index ee8fd1b4d9a327b9a0d1433e6d11722dd4cc41d1..da74607dafb7ada6f8077cd7a630c3ca2346b40b 100644 (file)
@@ -45,7 +45,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_OUTPUTFILE "$Id: FGOutputFile.h,v 1.3 2012/12/15 16:13:57 bcoconni Exp $"
+#define ID_OUTPUTFILE "$Id: FGOutputFile.h,v 1.6 2014/05/04 17:00:27 bcoconni Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -106,8 +106,9 @@ public:
       the next call to SetStartNewOutput().
       @param name new name */
   void SetOutputName(const std::string& fname) {
-    Name = Filename = FDMExec->GetRootDir() + fname;
-    runID_postfix = 0;
+    Name = FDMExec->GetRootDir() + fname;
+    runID_postfix = -1;
+    Filename = std::string();
   }
   /** Generate the output. This is a pure method so it must be implemented by
       the classes that inherits from FGOutputFile.
index 60b3e7a3b2481b8dff165511d227e3f37fe0434f..b7ff26873c7c1f7608e70fc7866df31fd3270bab 100644 (file)
@@ -60,7 +60,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGOutputSocket.cpp,v 1.8 2014/01/13 10:46:00 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGOutputSocket.cpp,v 1.9 2014/02/17 05:01:22 jberndt Exp $");
 IDENT(IdHdr,ID_OUTPUTSOCKET);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -211,9 +211,7 @@ void FGOutputSocket::PrintHeaders(void)
     socket->Append("SL pressure");
     socket->Append("Ambient pressure");
     socket->Append("Turbulence Magnitude");
-    socket->Append("Turbulence Direction X");
-    socket->Append("Turbulence Direction Y");
-    socket->Append("Turbulence Direction Z");
+    socket->Append("Turbulence Direction");
     socket->Append("NWind");
     socket->Append("EWind");
     socket->Append("DWind");
@@ -337,7 +335,7 @@ void FGOutputSocket::Print(void)
     socket->Append(Atmosphere->GetPressureSL());
     socket->Append(Atmosphere->GetPressure());
     socket->Append(Winds->GetTurbMagnitude());
-    socket->Append(Winds->GetTurbDirection().Dump(","));
+    socket->Append(Winds->GetTurbDirection());
     socket->Append(Winds->GetTotalWindNED().Dump(","));
   }
   if (SubSystems & ssMassProps) {
index e6abcef35ddf667510b6531402b86558123427c4..c67b4dbf8713cb403c41b1e61b269c9a90730934 100644 (file)
@@ -64,7 +64,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGOutputTextFile.cpp,v 1.10 2014/01/13 10:46:00 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGOutputTextFile.cpp,v 1.11 2014/02/17 05:02:38 jberndt Exp $");
 IDENT(IdHdr,ID_OUTPUTTEXTFILE);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -179,8 +179,9 @@ bool FGOutputTextFile::OpenFile(void)
     outstream << "P_{SL} (psf)" + delimeter;
     outstream << "P_{Ambient} (psf)" + delimeter;
     outstream << "Turbulence Magnitude (ft/sec)" + delimeter;
-    outstream << "Turbulence X Direction (rad)" + delimeter + "Turbulence Y Direction (rad)" + delimeter + "Turbulence Z Direction (rad)" + delimeter;
-    outstream << "Wind V_{North} (ft/s)" + delimeter + "Wind V_{East} (ft/s)" + delimeter + "Wind V_{Down} (ft/s)";
+    outstream << "Turbulence X Direction (deg)" + delimeter;
+    outstream << "Wind V_{North} (ft/s)" + delimeter + "Wind V_{East} (ft/s)" + delimeter + "Wind V_{Down} (ft/s)" + delimeter;
+    outstream << "Roll Turbulence (deg/sec)" + delimeter + "Pitch Turbulence (deg/sec)" + delimeter + "Yaw Turbulence (deg/sec)";
   }
   if (SubSystems & ssMassProps) {
     outstream << delimeter;
@@ -194,6 +195,7 @@ bool FGOutputTextFile::OpenFile(void)
     outstream << "I_{zy}" + delimeter;
     outstream << "I_{zz}" + delimeter;
     outstream << "Mass" + delimeter;
+    outstream << "Weight" + delimeter;
     outstream << "X_{cg}" + delimeter + "Y_{cg}" + delimeter + "Z_{cg}";
   }
   if (SubSystems & ssPropagate) {
@@ -337,13 +339,15 @@ void FGOutputTextFile::Print(void)
     outstream << Atmosphere->GetPressureSL() << delimeter;
     outstream << Atmosphere->GetPressure() << delimeter;
     outstream << Winds->GetTurbMagnitude() << delimeter;
-    outstream << Winds->GetTurbDirection().Dump(delimeter) << delimeter;
-    outstream << Winds->GetTotalWindNED().Dump(delimeter);
+    outstream << Winds->GetTurbDirection() << delimeter;
+    outstream << Winds->GetTotalWindNED().Dump(delimeter) << delimeter;
+    outstream << (Winds->GetTurbPQR()*radtodeg).Dump(delimeter);
   }
   if (SubSystems & ssMassProps) {
     outstream << delimeter;
     outstream << MassBalance->GetJ().Dump(delimeter) << delimeter;
     outstream << MassBalance->GetMass() << delimeter;
+    outstream << MassBalance->GetWeight() << delimeter;
     outstream << MassBalance->GetXYZcg().Dump(delimeter);
   }
   if (SubSystems & ssPropagate) {
old mode 100755 (executable)
new mode 100644 (file)
index 72438c2..5a259ba
@@ -55,7 +55,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGScript.cpp,v 1.56 2014/01/13 10:46:01 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGScript.cpp,v 1.57 2014/05/17 15:33:08 jberndt Exp $");
 IDENT(IdHdr,ID_FGSCRIPT);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -138,9 +138,15 @@ bool FGScript::LoadScript(string script, double deltaT, const string initfile)
 
   // Set sim timing
 
-  StartTime = run_element->GetAttributeValueAsNumber("start");
+  if (run_element->HasAttribute("start")) StartTime = run_element->GetAttributeValueAsNumber("start");
   FDMExec->Setsim_time(StartTime);
-  EndTime   = run_element->GetAttributeValueAsNumber("end");
+  if (run_element->HasAttribute("end")) {
+    EndTime   = run_element->GetAttributeValueAsNumber("end");
+  } else {
+    cerr << "An end time (duration) for the script must be specified in the script <run> element." << endl;
+    return false;
+  }
+
   // Make sure that the desired time is reached and executed.
   EndTime += 0.99*FDMExec->GetDeltaT();
 
old mode 100755 (executable)
new mode 100644 (file)
index 2e32156..bae0bf1
@@ -44,7 +44,7 @@ FORWARD DECLARATIONS
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGXMLElement.cpp,v 1.45 2014/01/13 10:46:02 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGXMLElement.cpp,v 1.48 2014/05/17 15:31:17 jberndt Exp $");
 IDENT(IdHdr,ID_XMLELEMENT);
 
 bool Element::converterIsInitialized = false;
@@ -155,6 +155,8 @@ Element::Element(const string& nm)
     convert["PA"]["LBS/FT2"] = 1.0/convert["LBS/FT2"]["PA"];
     // Mass flow
     convert["KG/MIN"]["LBS/MIN"] = convert["KG"]["LBS"];
+    convert ["N/SEC"]["LBS/SEC"] = 0.224808943;
+    convert ["LBS/SEC"]["N/SEC"] = 1.0/convert ["N/SEC"]["LBS/SEC"];
     // Fuel Consumption
     convert["LBS/HP*HR"]["KG/KW*HR"] = 0.6083;
     convert["KG/KW*HR"]["LBS/HP*HR"] = 1.0/convert["LBS/HP*HR"]["KG/KW*HR"];
@@ -226,6 +228,7 @@ Element::Element(const string& nm)
     convert["LBS/SEC"]["LBS/SEC"] = 1.00;
     convert["KG/MIN"]["KG/MIN"] = 1.0;
     convert["LBS/MIN"]["LBS/MIN"] = 1.0;
+    convert["N/SEC"]["N/SEC"] = 1.0;
     // Fuel Consumption
     convert["LBS/HP*HR"]["LBS/HP*HR"] = 1.0;
     convert["KG/KW*HR"]["KG/KW*HR"] = 1.0;
@@ -568,24 +571,36 @@ double Element::DisperseValue(Element *e, double val, const std::string supplied
 {
   double value=val;
   double disp=0.0;
-  if (e->HasAttribute("dispersion")) {
+
+  bool disperse = false;
+  try {
+    char* num = getenv("JSBSIM_DISPERSE");
+    if (num) {
+      disperse = (atoi(num) == 1);  // set dispersions
+    }
+  } catch (...) {                   // if error set to false
+    disperse = false;
+    std::cerr << "Could not process JSBSIM_DISPERSE environment variable: Assumed NO dispersions." << endl;
+  }
+
+  if (e->HasAttribute("dispersion") && disperse) {
     disp = e->GetAttributeValueAsNumber("dispersion");
     if (!supplied_units.empty()) disp *= convert[supplied_units][target_units];
     string attType = e->GetAttributeValue("type");
-    if (attType == "gaussian") {
+    if (attType == "gaussian" || attType == "gaussiansigned") {
       double grn = GaussianRandomNumber();
+    if (attType == "gaussian") {
       value = val + disp*grn;
-/*      std::cout << "DISPERSION GAUSSIAN: Initial: " << val
-                << "  Dispersion: " << disp
-                << "  Gaussian Rand Num: " << grn
-                << "  Total Dispersed Value: " << value << endl; */
-    } else if (attType == "uniform") {
+      } else { // Assume gaussiansigned
+        value = (val + disp*grn)*(fabs(grn)/grn);
+      }
+    } else if (attType == "uniform" || attType == "uniformsigned") {
       double urn = ((((double)rand()/RAND_MAX)-0.5)*2.0);
+      if (attType == "uniform") {
       value = val + disp * urn;
-/*      std::cout << "DISPERSION UNIFORM: Initial: " << val
-                << "  Dispersion: " << disp
-                << "  Uniform Rand Num: " << urn
-                << "  Total Dispersed Value: " << value << endl; */
+      } else { // Assume uniformsigned
+        value = (val + disp * urn)*(fabs(urn)/urn);
+      }
     } else {
       cerr << ReadFrom() << "Unknown dispersion type" << attType << endl;
       exit(-1);
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
index 9bb120b04bdcf3b8a9346b38754e09968379e5e4..808776101205886267453797ec1c9c13a1d611a6 100644 (file)
@@ -49,7 +49,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_STRINGUTILS "$Id: string_utilities.h,v 1.18 2014/01/13 10:46:03 ehofman Exp $"
+#define ID_STRINGUTILS "$Id: string_utilities.h,v 1.19 2014/01/29 13:30:11 ehofman Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -74,7 +74,7 @@ CLASS DECLARATION
   extern bool is_number(const std::string& str);
   std::vector <std::string> split(std::string str, char d);
 
-// libc++ has these as built-ins for all C++ language versions
+  // libc++ has these as built-ins for all C++ language versions
 #if !defined(_LIBCPP_VERSION)
   extern std::string to_string(int);
   extern std::string to_string(double);
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
index 77f080ba131446557401f97714a71564e4a36ad5..4da4c08563561e1d80b13de41867559b8b4f2eb1 100644 (file)
@@ -16,6 +16,7 @@
  * with this program.  If not, see <http://www.gnu.org/licenses/>.
  */
 
+#include "initialization/FGInitialCondition.h"
 #include "FGStateSpace.h"
 #include <limits>
 #include <iomanip>
index 9d97c937aea37084840e5be3019d1ba130fcafed..a7aedb19e87e44b68af21ebf73b85ab9f97024f1 100644 (file)
@@ -51,7 +51,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGAerodynamics.cpp,v 1.52 2014/01/13 10:46:04 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGAerodynamics.cpp,v 1.53 2014/05/17 15:30:35 jberndt Exp $");
 IDENT(IdHdr,ID_AERODYNAMICS);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -300,6 +300,8 @@ bool FGAerodynamics::Load(Element *element)
     document = element;
   }
 
+  Name = "Aerodynamics Model: " + document->GetAttributeValue("name");
+
   FGModel::Load(document); // Perform base class Pre-Load
 
   DetermineAxisSystem(document); // Detemine if Lift/Side/Drag, etc. is used.
@@ -483,47 +485,25 @@ void FGAerodynamics::bind(void)
 {
   typedef double (FGAerodynamics::*PMF)(int) const;
 
-  PropertyManager->Tie("forces/fbx-aero-lbs", this,1,
-                       (PMF)&FGAerodynamics::GetForces);
-  PropertyManager->Tie("forces/fby-aero-lbs", this,2,
-                       (PMF)&FGAerodynamics::GetForces);
-  PropertyManager->Tie("forces/fbz-aero-lbs", this,3,
-                       (PMF)&FGAerodynamics::GetForces);
-  PropertyManager->Tie("moments/l-aero-lbsft", this,1,
-                       (PMF)&FGAerodynamics::GetMoments);
-  PropertyManager->Tie("moments/m-aero-lbsft", this,2,
-                       (PMF)&FGAerodynamics::GetMoments);
-  PropertyManager->Tie("moments/n-aero-lbsft", this,3,
-                       (PMF)&FGAerodynamics::GetMoments);
-  PropertyManager->Tie("forces/fwx-aero-lbs", this,1,
-                       (PMF)&FGAerodynamics::GetvFw);
-  PropertyManager->Tie("forces/fwy-aero-lbs", this,2,
-                       (PMF)&FGAerodynamics::GetvFw);
-  PropertyManager->Tie("forces/fwz-aero-lbs", this,3,
-                       (PMF)&FGAerodynamics::GetvFw);
-  PropertyManager->Tie("forces/lod-norm", this,
-                       &FGAerodynamics::GetLoD);
-  PropertyManager->Tie("aero/cl-squared", this,
-                       &FGAerodynamics::GetClSquared);
+  PropertyManager->Tie("forces/fbx-aero-lbs",  this, 1, (PMF)&FGAerodynamics::GetForces);
+  PropertyManager->Tie("forces/fby-aero-lbs",  this, 2, (PMF)&FGAerodynamics::GetForces);
+  PropertyManager->Tie("forces/fbz-aero-lbs",  this, 3, (PMF)&FGAerodynamics::GetForces);
+  PropertyManager->Tie("moments/l-aero-lbsft", this, 1, (PMF)&FGAerodynamics::GetMoments);
+  PropertyManager->Tie("moments/m-aero-lbsft", this, 2, (PMF)&FGAerodynamics::GetMoments);
+  PropertyManager->Tie("moments/n-aero-lbsft", this, 3, (PMF)&FGAerodynamics::GetMoments);
+  PropertyManager->Tie("forces/fwx-aero-lbs",  this, 1, (PMF)&FGAerodynamics::GetvFw);
+  PropertyManager->Tie("forces/fwy-aero-lbs",  this, 2, (PMF)&FGAerodynamics::GetvFw);
+  PropertyManager->Tie("forces/fwz-aero-lbs",  this, 3, (PMF)&FGAerodynamics::GetvFw);
+  PropertyManager->Tie("forces/lod-norm",      this, &FGAerodynamics::GetLoD);
+  PropertyManager->Tie("aero/cl-squared",      this, &FGAerodynamics::GetClSquared);
   PropertyManager->Tie("aero/qbar-area", &qbar_area);
-  PropertyManager->Tie("aero/alpha-max-rad", this,
-                       &FGAerodynamics::GetAlphaCLMax,
-                       &FGAerodynamics::SetAlphaCLMax,
-                       true);
-  PropertyManager->Tie("aero/alpha-min-rad", this,
-                       &FGAerodynamics::GetAlphaCLMin,
-                       &FGAerodynamics::SetAlphaCLMin,
-                       true);
-  PropertyManager->Tie("aero/bi2vel", this,
-                       &FGAerodynamics::GetBI2Vel);
-  PropertyManager->Tie("aero/ci2vel", this,
-                       &FGAerodynamics::GetCI2Vel);
-  PropertyManager->Tie("aero/alpha-wing-rad", this,
-                       &FGAerodynamics::GetAlphaW);
-  PropertyManager->Tie("systems/stall-warn-norm", this,
-                        &FGAerodynamics::GetStallWarn);
-  PropertyManager->Tie("aero/stall-hyst-norm", this,
-                        &FGAerodynamics::GetHysteresisParm);
+  PropertyManager->Tie("aero/alpha-max-rad",   this, &FGAerodynamics::GetAlphaCLMax, &FGAerodynamics::SetAlphaCLMax, true);
+  PropertyManager->Tie("aero/alpha-min-rad",   this, &FGAerodynamics::GetAlphaCLMin, &FGAerodynamics::SetAlphaCLMin, true);
+  PropertyManager->Tie("aero/bi2vel",          this, &FGAerodynamics::GetBI2Vel);
+  PropertyManager->Tie("aero/ci2vel",          this, &FGAerodynamics::GetCI2Vel);
+  PropertyManager->Tie("aero/alpha-wing-rad",  this, &FGAerodynamics::GetAlphaW);
+  PropertyManager->Tie("systems/stall-warn-norm", this, &FGAerodynamics::GetStallWarn);
+  PropertyManager->Tie("aero/stall-hyst-norm", this, &FGAerodynamics::GetHysteresisParm);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index 0c7d90f5e3bee9a234b4895ed3697dd71fce6cef..9bca6cd2986af92c8803b85c210d619d479edcb8 100644 (file)
@@ -60,7 +60,7 @@ DEFINITIONS
 GLOBAL DATA
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-IDENT(IdSrc,"$Id: FGAircraft.cpp,v 1.39 2014/01/13 10:46:04 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGAircraft.cpp,v 1.40 2014/05/17 15:29:30 jberndt Exp $");
 IDENT(IdHdr,ID_AIRCRAFT);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -204,9 +204,9 @@ void FGAircraft::bind(void)
   PropertyManager->Tie("metrics/lv-norm", this, &FGAircraft::Getlbarv);
   PropertyManager->Tie("metrics/vbarh-norm", this, &FGAircraft::Getvbarh);
   PropertyManager->Tie("metrics/vbarv-norm", this, &FGAircraft::Getvbarv);
-  PropertyManager->Tie("metrics/aero-rp-x-in", this, eX, (PMF)&FGAircraft::GetXYZrp);
-  PropertyManager->Tie("metrics/aero-rp-y-in", this, eY, (PMF)&FGAircraft::GetXYZrp);
-  PropertyManager->Tie("metrics/aero-rp-z-in", this, eZ, (PMF)&FGAircraft::GetXYZrp);
+  PropertyManager->Tie("metrics/aero-rp-x-in", this, eX, (PMF)&FGAircraft::GetXYZrp, &FGAircraft::SetXYZrp);
+  PropertyManager->Tie("metrics/aero-rp-y-in", this, eY, (PMF)&FGAircraft::GetXYZrp, &FGAircraft::SetXYZrp);
+  PropertyManager->Tie("metrics/aero-rp-z-in", this, eZ, (PMF)&FGAircraft::GetXYZrp, &FGAircraft::SetXYZrp);
   PropertyManager->Tie("metrics/eyepoint-x-in", this, eX, (PMF)&FGAircraft::GetXYZep);
   PropertyManager->Tie("metrics/eyepoint-y-in", this, eY,(PMF)&FGAircraft::GetXYZep);
   PropertyManager->Tie("metrics/eyepoint-z-in", this, eZ, (PMF)&FGAircraft::GetXYZep);
index 5ad8ad3b2ddde231eb961edab74059043a1e2f47..d3576d115505c6a16ce95beaf9c665d5eaa34bb6 100644 (file)
@@ -50,7 +50,7 @@ INCLUDES
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGAtmosphere.cpp,v 1.58 2014/01/13 10:46:04 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGAtmosphere.cpp,v 1.59 2014/05/07 19:51:43 bcoconni Exp $");
 IDENT(IdHdr,ID_ATMOSPHERE);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -244,8 +244,8 @@ double FGAtmosphere::ConvertFromPSF(double p, ePressure unit) const
 
 void FGAtmosphere::bind(void)
 {
-  typedef double (FGAtmosphere::*PMFi)(int) const;
-  typedef void (FGAtmosphere::*PMF)(int, double);
+//  typedef double (FGAtmosphere::*PMFi)(int) const;
+//  typedef void (FGAtmosphere::*PMF)(int, double);
   PropertyManager->Tie("atmosphere/T-R", this, &FGAtmosphere::GetTemperature);
   PropertyManager->Tie("atmosphere/rho-slugs_ft3", this, &FGAtmosphere::GetDensity);
   PropertyManager->Tie("atmosphere/P-psf", this, &FGAtmosphere::GetPressure);
old mode 100755 (executable)
new mode 100644 (file)
index 07133bc..3978f22
@@ -43,6 +43,7 @@ INCLUDES
 #include <iostream>
 
 #include "FGAuxiliary.h"
+#include "initialization/FGInitialCondition.h"
 #include "FGFDMExec.h"
 #include "input_output/FGPropertyManager.h"
 
@@ -50,7 +51,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGAuxiliary.cpp,v 1.65 2014/01/13 10:46:06 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGAuxiliary.cpp,v 1.67 2014/05/17 15:28:51 jberndt Exp $");
 IDENT(IdHdr,ID_AUXILIARY);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -165,7 +166,7 @@ bool FGAuxiliary::Run(bool Holding)
 
   double Vt2 = Vt*Vt;
 
-  if ( Vt > 1.0 ) {
+  if ( Vt > 0.001 ) {
     if (vAeroUVW(eW) != 0.0)
       alpha = AeroU2 > 0.0 ? atan2(vAeroUVW(eW), vAeroUVW(eU)) : 0.0;
     if (vAeroUVW(eV) != 0.0)
@@ -174,7 +175,7 @@ bool FGAuxiliary::Run(bool Holding)
     //double signU=1;
     //if (vAeroUVW(eU) < 0.0) signU=-1;
 
-    if ( mUW >= 1.0 ) {
+    if ( mUW >= 0.001 ) {
       adot = (vAeroUVW(eU)*in.vUVWdot(eW) - vAeroUVW(eW)*in.vUVWdot(eU))/mUW;
       // bdot = (signU*mUW*in.vUVWdot(eV)
       //        - vAeroUVW(eV)*(vAeroUVW(eU)*in.vUVWdot(eU) + vAeroUVW(eW)*in.vUVWdot(eW)))/(Vt2*sqrt(mUW));
@@ -221,7 +222,7 @@ bool FGAuxiliary::Run(bool Holding)
   if (abs(MachU) > 0.0) {
     vcas = sqrt(7 * in.PressureSL / in.DensitySL * (A-1));
     veas = sqrt(2 * qbar / in.DensitySL);
-    vtrue = 1116.43559 * MachU * sqrt(in.Temperature / 518.67);
+    vtrue = 1116.43559 * Mach * sqrt(in.Temperature / 518.67);
   } else {
     vcas = veas = vtrue = 0.0;
   }
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
index fcb9a3f358ecf20b741a9430f438ad4dad4e66ec..2c7d3bedb4211569331d6b3e08a129b7a5d3aef5 100644 (file)
@@ -71,7 +71,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGFCS.cpp,v 1.87 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGFCS.cpp,v 1.88 2014/05/17 15:27:16 jberndt Exp $");
 IDENT(IdHdr,ID_FCS);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -523,6 +523,8 @@ bool FGFCS::Load(Element* el, SystemType systype)
     document = el;
   }
 
+  Name = "Flight Control Systems Model: " + document->GetAttributeValue("name");
+
   if (document->GetName() == "autopilot") {
     Name = "Autopilot: " + document->GetAttributeValue("name");
   } else if (document->GetName() == "flight_control") {
old mode 100755 (executable)
new mode 100644 (file)
index b628a49f8720bba076babb67a7b10fb1ee052395..478703842aa117e6a69f1138d874929f7120a9e4 100644 (file)
@@ -49,7 +49,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGGroundReactions.cpp,v 1.49 2014/01/28 09:42:21 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGGroundReactions.cpp,v 1.50 2014/05/17 15:25:20 jberndt Exp $");
 IDENT(IdHdr,ID_GROUNDREACTIONS);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -156,6 +156,8 @@ bool FGGroundReactions::Load(Element* elem)
     document = elem;
   }
 
+  Name = "Ground Reactions Model: " + document->GetAttributeValue("name");
+
   Debug(2);
 
   unsigned int numContacts = document->GetNumElements("contact");
index 8a6aeec3f4a4e10b17c5c0a6a226fe96ebfab46f..9807a9bc36d874067c51cd93f7bca4357f56cc65 100644 (file)
@@ -43,7 +43,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGInertial.cpp,v 1.29 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGInertial.cpp,v 1.31 2014/05/17 15:24:37 jberndt Exp $");
 IDENT(IdHdr,ID_INERTIAL);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -57,12 +57,14 @@ FGInertial::FGInertial(FGFDMExec* fgex) : FGModel(fgex)
 
   // Earth defaults
   RotationRate    = 0.00007292115;
-  GM              = 14.07644180E15;     // WGS84 value
-  RadiusReference = 20925650.00;        // Equatorial radius (WGS84)
+//  RotationRate    = 0.000072921151467;
+  GM              = 14.0764417572E15;   // WGS84 value
   C2_0            = -4.84165371736E-04; // WGS84 value for the C2,0 coefficient
-  J2              = 1.0826266836E-03;   // WGS84 value for J2
-  a               = 20925646.3255;      // WGS84 semimajor axis length in feet
+  J2              = 1.08262982E-03;     // WGS84 value for J2
+  a               = 20925646.32546;     // WGS84 semimajor axis length in feet
+//  a               = 20902254.5305;      // Effective Earth radius for a sphere
   b               = 20855486.5951;      // WGS84 semiminor axis length in feet
+  RadiusReference = a;
 
   // Lunar defaults
   /*
old mode 100755 (executable)
new mode 100644 (file)
index dbd590dac6ec917b83dc5f495eee89e7468ef113..2dbc8b08c5652de2c9400e29d0fd2cf2e103790c 100644 (file)
@@ -62,7 +62,7 @@ DEFINITIONS
 GLOBAL DATA
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-IDENT(IdSrc,"$Id: FGLGear.cpp,v 1.114 2014/01/28 09:42:21 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGLGear.cpp,v 1.116 2014/05/17 15:26:39 jberndt Exp $");
 IDENT(IdHdr,ID_LGEAR);
 
 // Body To Structural (body frame is rotated 180 deg about Y and lengths are given in
@@ -562,7 +562,7 @@ void FGLGear::CrashDetect(void)
       SinkRate > 1.4666*30 ) && !fdmex->IntegrationSuspended())
   {
     PutMessage("Crash Detected: Simulation FREEZE.");
-    fdmex->SuspendIntegration();
+    // fdmex->SuspendIntegration();
   }
 }
 
index 3d24d1b3b38575a7e37fc4b94ea691db8d90f8c4..64a15b3db15d44e92bc37cbc65bf85f61bdec233 100644 (file)
@@ -52,7 +52,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGMassBalance.cpp,v 1.47 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGMassBalance.cpp,v 1.49 2014/05/17 15:17:13 jberndt Exp $");
 IDENT(IdHdr,ID_MASSBALANCE);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -121,6 +121,8 @@ bool FGMassBalance::Load(Element* elem)
     document = elem;
   }
 
+  Name = "Mass Properties Model: " + document->GetAttributeValue("name");
+
   FGModel::Load(document); // Perform base class Load.
 
   bixx = biyy = bizz = bixy = bixz = biyz = 0.0;
@@ -399,6 +401,8 @@ void FGMassBalance::bind(void)
                        (PMF)&FGMassBalance::GetXYZcg);
   PropertyManager->Tie("inertia/cg-z-in", this,3,
                        (PMF)&FGMassBalance::GetXYZcg);
+  typedef int (FGMassBalance::*iOPV)() const;
+  PropertyManager->Tie("inertia/print-mass-properties", this, (iOPV)0, &FGMassBalance::GetMassPropertiesReport);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -423,7 +427,7 @@ void FGMassBalance::PointMass::bind(FGPropertyManager* PropertyManager, int num)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGMassBalance::GetMassPropertiesReport(void) const
+void FGMassBalance::GetMassPropertiesReport(int i)
 {
   cout << endl << fgblue << highint 
        << "  Mass Properties Report (English units: lbf, in, slug-ft^2)"
index 833bb1a5418c3cecf44f6cca2fbd93402724e1bd..2c783ad87a928fc9bca82cc1d6c37921c24fe694 100644 (file)
@@ -48,7 +48,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_MASSBALANCE "$Id: FGMassBalance.h,v 1.29 2013/11/24 11:40:56 bcoconni Exp $"
+#define ID_MASSBALANCE "$Id: FGMassBalance.h,v 1.31 2014/05/17 15:17:13 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONSS
@@ -176,7 +176,7 @@ public:
   const FGMatrix33& GetJ(void) const {return mJ;}
   const FGMatrix33& GetJinv(void) const {return mJinv;}
   void SetAircraftBaseInertias(const FGMatrix33& BaseJ) {baseJ = BaseJ;}
-  void GetMassPropertiesReport(void) const;
+  void GetMassPropertiesReport(int i);
   
   struct Inputs {
     double GasMass;
@@ -259,7 +259,10 @@ private:
     const string& GetName(void) {return Name;}
 
     void SetPointMassLocation(int axis, double value) {Location(axis) = value;}
-    void SetPointMassWeight(double wt) {Weight = wt;}
+    void SetPointMassWeight(double wt) {
+      Weight = wt;
+      CalculateShapeInertia();
+    }
     void SetPointMassShapeType(esShape st) {eShapeType = st;}
     void SetRadius(double r) {Radius = r;}
     void SetLength(double l) {Length = l;}
index 6564df5e4030639588a615407d0fdc905f536511..d46c192f392358511c91b63aa29ef1e4a43015de 100644 (file)
@@ -69,6 +69,7 @@ INCLUDES
 #include <iomanip>
 #include <fstream>
 
+#include "initialization/FGInitialCondition.h"
 #include "FGPropagate.h"
 #include "FGGroundReactions.h"
 #include "FGFDMExec.h"
@@ -78,7 +79,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGPropagate.cpp,v 1.123 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGPropagate.cpp,v 1.125 2014/05/17 15:15:53 jberndt Exp $");
 IDENT(IdHdr,ID_PROPAGATE);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -100,10 +101,10 @@ FGPropagate::FGPropagate(FGFDMExec* fdmex)
   integrator_rotational_position = eRectEuler;
   integrator_translational_position = eAdamsBashforth3;
 
-  VState.dqPQRidot.resize(4, FGColumnVector3(0.0,0.0,0.0));
-  VState.dqUVWidot.resize(4, FGColumnVector3(0.0,0.0,0.0));
-  VState.dqInertialVelocity.resize(4, FGColumnVector3(0.0,0.0,0.0));
-  VState.dqQtrndot.resize(4, FGQuaternion(0.0,0.0,0.0));
+  VState.dqPQRidot.resize(5, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqUVWidot.resize(5, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqInertialVelocity.resize(5, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqQtrndot.resize(5, FGQuaternion(0.0,0.0,0.0));
 
   bind();
   Debug(0);
@@ -126,10 +127,10 @@ bool FGPropagate::InitModel(void)
   VState.vLocation.SetEllipse(in.SemiMajor, in.SemiMinor);
   VState.vLocation.SetAltitudeAGL(4.0, FDMExec->GetSimTime());
 
-  VState.dqPQRidot.resize(4, FGColumnVector3(0.0,0.0,0.0));
-  VState.dqUVWidot.resize(4, FGColumnVector3(0.0,0.0,0.0));
-  VState.dqInertialVelocity.resize(4, FGColumnVector3(0.0,0.0,0.0));
-  VState.dqQtrndot.resize(4, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqPQRidot.resize(5, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqUVWidot.resize(5, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqInertialVelocity.resize(5, FGColumnVector3(0.0,0.0,0.0));
+  VState.dqQtrndot.resize(5, FGColumnVector3(0.0,0.0,0.0));
 
   integrator_rotational_rate = eRectEuler;
   integrator_translational_rate = eAdamsBashforth2;
@@ -187,7 +188,7 @@ void FGPropagate::SetInitialState(const FGInitialCondition *FGIC)
 
 void FGPropagate::InitializeDerivatives()
 {
-  for (int i=0; i<4; i++) {
+  for (int i=0; i<5; i++) {
     VState.dqPQRidot[i] = in.vPQRidot;
     VState.dqUVWidot[i] = in.vUVWidot;
     VState.dqInertialVelocity[i] = VState.vInertialVelocity;
@@ -312,8 +313,14 @@ void FGPropagate::Integrate( FGColumnVector3& Integrand,
     break;
   case eAdamsBashforth4: Integrand += (1/24.0)*dt*(55.0*ValDot[0] - 59.0*ValDot[1] + 37.0*ValDot[2] - 9.0*ValDot[3]);
     break;
+  case eAdamsBashforth5: Integrand += dt*((1901./720.)*ValDot[0] - (1387./360.)*ValDot[1] + (109./30.)*ValDot[2] - (637./360.)*ValDot[3] + (251./720.)*ValDot[4]);
+    break;
   case eNone: // do nothing, freeze translational rate
     break;
+  case eBuss1:
+  case eBuss2:
+  case eLocalLinearization:
+    throw("Can only use Buss (1 & 2) or local linearization integration methods in for rotational position!");
   default:
     break;
   }
@@ -341,6 +348,8 @@ void FGPropagate::Integrate( FGQuaternion& Integrand,
     break;
   case eAdamsBashforth4: Integrand += (1/24.0)*dt*(55.0*ValDot[0] - 59.0*ValDot[1] + 37.0*ValDot[2] - 9.0*ValDot[3]);
     break;
+  case eAdamsBashforth5: Integrand += dt*((1901./720.)*ValDot[0] - (1387./360.)*ValDot[1] + (109./30.)*ValDot[2] - (637./360.)*ValDot[3] + (251./720.)*ValDot[4]);
+    break;
   case eBuss1:
     {
       // This is the first order method as described in Samuel R. Buss paper[6].
index f0f0129280ceaf9466e2b6c2953cdbce8021fa69..a3c3a2702ac3cf0bcd137666bb1e7cd0e29cdfb8 100644 (file)
@@ -49,7 +49,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_PROPAGATE "$Id: FGPropagate.h,v 1.80 2013/12/22 17:08:59 jberndt Exp $"
+#define ID_PROPAGATE "$Id: FGPropagate.h,v 1.81 2014/05/17 15:15:53 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -93,7 +93,7 @@ CLASS DOCUMENTATION
     @endcode
 
     @author Jon S. Berndt, Mathias Froehlich, Bertrand Coconnier
-    @version $Id: FGPropagate.h,v 1.80 2013/12/22 17:08:59 jberndt Exp $
+    @version $Id: FGPropagate.h,v 1.81 2014/05/17 15:15:53 jberndt Exp $
   */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -159,7 +159,7 @@ public:
 
   /// These define the indices use to select the various integrators.
   enum eIntegrateType {eNone = 0, eRectEuler, eTrapezoidal, eAdamsBashforth2,
-                       eAdamsBashforth3, eAdamsBashforth4, eBuss1, eBuss2, eLocalLinearization};
+                       eAdamsBashforth3, eAdamsBashforth4, eBuss1, eBuss2, eLocalLinearization, eAdamsBashforth5};
 
   /** Initializes the FGPropagate class after instantiation and prior to first execution.
       The base class FGModel::InitModel is called first, initializing pointers to the
@@ -312,6 +312,11 @@ public:
   */
   FGColumnVector3 GetECEFVelocity(void) const {return Tb2ec * VState.vUVW; }
 
+  /** Calculates and retrieves the velocity vector relative to the earth centered earth fixed (ECEF) frame
+      for a particular axis.
+  */
+  double GetECEFVelocity(int idx) const {return (Tb2ec * VState.vUVW)(idx); }
+
   /** Returns the current altitude above sea level.
       This function returns the altitude above sea level.
       units ft
index 580653a6289d180a9c941e1e5e39bb599684840d..1bcae7205fc2313c556ae36be6417243ce8e113a 100644 (file)
@@ -67,7 +67,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGPropulsion.cpp,v 1.76 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGPropulsion.cpp,v 1.78 2014/05/17 15:13:56 jberndt Exp $");
 IDENT(IdHdr,ID_PROPULSION);
 
 extern short debug_lvl;
@@ -81,7 +81,6 @@ FGPropulsion::FGPropulsion(FGFDMExec* exec) : FGModel(exec)
 {
   Name = "FGPropulsion";
 
-  InitializedEngines = 0;
   numSelectedFuelTanks = numSelectedOxiTanks = 0;
   numTanks = numEngines = 0;
   numOxiTanks = numFuelTanks = 0;
@@ -97,7 +96,6 @@ FGPropulsion::FGPropulsion(FGFDMExec* exec) : FGModel(exec)
   HaveRocketEngine =
   HaveTurboPropEngine =
   HaveElectricEngine = false;
-  HasInitializedEngines = false;
 
   Debug(0);
 }
@@ -126,30 +124,8 @@ bool FGPropulsion::InitModel(void)
 
   for (unsigned int i=0; i<numTanks; i++) Tanks[i]->ResetToIC();
 
-  for (unsigned int i=0; i<numEngines; i++) {
-    switch (Engines[i]->GetType()) {
-      case FGEngine::etPiston:
-        Engines[i]->ResetToIC();
-        try {
-          if (HasInitializedEngines && (InitializedEngines & i)) InitRunning(i);
-        } catch (string str) {
-          cerr << str << endl;
-          result = false;
-        }
-        break;
-      case FGEngine::etTurbine:
-        Engines[i]->ResetToIC();
-        try {
-          if (HasInitializedEngines && (InitializedEngines & i)) InitRunning(i);
-        } catch (string str) {
-          cerr << str << endl;
-          result = false;
-        }
-        break;
-      default:
-        break;
-    }
-  }
+  for (unsigned int i=0; i<numEngines; i++)
+    Engines[i]->ResetToIC();
 
   return result;
 }
@@ -289,7 +265,8 @@ void FGPropulsion::ConsumeFuel(FGEngine* engine)
 
   if (engine->GetType() == FGEngine::etRocket) {
     double OxidizerToBurn = engine->CalcOxidizerNeed();                // How much fuel does this engine need?
-    double OxidizerNeededPerTank = OxidizerToBurn / TanksWithOxidizer; // Determine fuel needed per tank.  
+    double OxidizerNeededPerTank = 0;
+    if (TanksWithOxidizer > 0) OxidizerNeededPerTank = OxidizerToBurn / TanksWithOxidizer; // Determine fuel needed per tank.  
     for (unsigned int i=0; i<FeedListOxi.size(); i++) {
       Tanks[FeedListOxi[i]]->Drain(OxidizerNeededPerTank); 
     }
@@ -358,9 +335,6 @@ void FGPropulsion::InitRunning(int n)
     GetEngine(n)->InitRunning();
     GetSteadyState();
 
-    InitializedEngines = 1 << n;
-    HasInitializedEngines = true;
-
   } else if (n < 0) { // -1 refers to "All Engines"
 
     for (unsigned int i=0; i<GetNumEngines(); i++) {
@@ -370,8 +344,6 @@ void FGPropulsion::InitRunning(int n)
     }
 
     GetSteadyState();
-    InitializedEngines = -1;
-    HasInitializedEngines = true;
   }
 }
 
@@ -397,6 +369,8 @@ bool FGPropulsion::Load(Element* elem)
     el = elem;
   }
 
+  Name = "Propulsion Model: " + el->GetAttributeValue("name");
+
   FGModel::Load(el); // Perform base class Load.
 
   // Process tank definitions first to establish the number of fuel tanks
@@ -837,19 +811,12 @@ void FGPropulsion::bind(void)
                         &FGPropulsion::SetRefuel, true);
   PropertyManager->Tie("propulsion/fuel_dump", this, &FGPropulsion::GetFuelDump,
                         &FGPropulsion::SetFuelDump, true);
-  PropertyManager->Tie("forces/fbx-prop-lbs", this,1,
-                       (PMF)&FGPropulsion::GetForces);
-  PropertyManager->Tie("forces/fby-prop-lbs", this,2,
-                       (PMF)&FGPropulsion::GetForces);
-  PropertyManager->Tie("forces/fbz-prop-lbs", this,3,
-                       (PMF)&FGPropulsion::GetForces);
-  PropertyManager->Tie("moments/l-prop-lbsft", this,1,
-                       (PMF)&FGPropulsion::GetMoments);
-  PropertyManager->Tie("moments/m-prop-lbsft", this,2,
-                       (PMF)&FGPropulsion::GetMoments);
-  PropertyManager->Tie("moments/n-prop-lbsft", this,3,
-                       (PMF)&FGPropulsion::GetMoments);
-
+  PropertyManager->Tie("forces/fbx-prop-lbs", this, eX, (PMF)&FGPropulsion::GetForces);
+  PropertyManager->Tie("forces/fby-prop-lbs", this, eY, (PMF)&FGPropulsion::GetForces);
+  PropertyManager->Tie("forces/fbz-prop-lbs", this, eZ, (PMF)&FGPropulsion::GetForces);
+  PropertyManager->Tie("moments/l-prop-lbsft", this, eX, (PMF)&FGPropulsion::GetMoments);
+  PropertyManager->Tie("moments/m-prop-lbsft", this, eY, (PMF)&FGPropulsion::GetMoments);
+  PropertyManager->Tie("moments/n-prop-lbsft", this, eZ, (PMF)&FGPropulsion::GetMoments);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index cca5adf0003f4db613adfa0879b6d577709fff64..a04916ada590f12a28fd4095292cef69115a3d5e 100644 (file)
@@ -49,7 +49,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_PROPULSION "$Id: FGPropulsion.h,v 1.32 2013/11/24 11:40:56 bcoconni Exp $"
+#define ID_PROPULSION "$Id: FGPropulsion.h,v 1.33 2014/04/13 11:19:15 bcoconni Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -91,7 +91,7 @@ CLASS DOCUMENTATION
   @endcode
 
     @author Jon S. Berndt
-    @version $Id: FGPropulsion.h,v 1.32 2013/11/24 11:40:56 bcoconni Exp $
+    @version $Id: FGPropulsion.h,v 1.33 2014/04/13 11:19:15 bcoconni Exp $
     @see
     FGEngine
     FGTank
@@ -225,9 +225,6 @@ private:
   bool HaveElectricEngine;
   void ConsumeFuel(FGEngine* engine);
 
-  int InitializedEngines;
-  bool HasInitializedEngines;
-
   void bind();
   void Debug(int from);
 };
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
index 664b3274ab30ce4355d386a9106a2cc53240ccff..a5f6e8e54dcb00c859f65951e6f2cca3ec77df7d 100644 (file)
@@ -50,7 +50,7 @@ INCLUDES
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGStandardAtmosphere.cpp,v 1.23 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGStandardAtmosphere.cpp,v 1.24 2014/05/17 15:07:48 jberndt Exp $");
 IDENT(IdHdr,ID_STANDARDATMOSPHERE);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -72,15 +72,28 @@ FGStandardAtmosphere::FGStandardAtmosphere(FGFDMExec* fdmex) : FGAtmosphere(fdme
   //                        GeoMet Alt    Temp      GeoPot Alt  GeoMet Alt
   //                           (ft)      (deg R)      (km)        (km)
   //                         --------   --------    ----------  ----------
-  *StdAtmosTemperatureTable <<      0.0 << 518.67 //    0.000       0.000
-                            <<  36151.6 << 390.0  //   11.000      11.019
-                            <<  65823.5 << 390.0  //   20.000      20.063
-                            << 105518.4 << 411.6  //   32.000      32.162
-                            << 155347.8 << 487.2  //   47.000      47.350
-                            << 168677.8 << 487.2  //   51.000      51.413
-                            << 235570.9 << 386.4  //   71.000      71.802
-                            << 282152.2 << 336.5  //   84.852      86.000
-                            << 298556.4 << 336.5; //               91.000 - First layer in high altitude regime 
+  //*StdAtmosTemperatureTable <<      0.00 << 518.67  //    0.000       0.000
+  //                          <<  36151.80 << 389.97  //   11.000      11.019
+  //                          <<  65823.90 << 389.97  //   20.000      20.063
+  //                          << 105518.06 << 411.60  //   32.000      32.162
+  //                          << 155348.07 << 487.20  //   47.000      47.350
+  //                          << 168676.12 << 487.20  //   51.000      51.413
+  //                          << 235570.77 << 386.40  //   71.000      71.802
+  //                          << 282152.08 << 336.50  //   84.852      86.000
+  //                          << 298556.40 << 336.50; //               91.000 - First layer in high altitude regime 
+
+  //                            GeoPot Alt    Temp       GeoPot Alt  GeoMet Alt
+  //                               (ft)      (deg R)        (km)        (km)
+  //                           -----------   --------     ----------  ----------
+  *StdAtmosTemperatureTable <<      0.0000 << 518.67  //    0.000       0.000
+                            <<  36089.2388 << 389.97  //   11.000      11.019
+                            <<  65616.7979 << 389.97  //   20.000      20.063
+                            << 104986.8766 << 411.57  //   32.000      32.162
+                            << 154199.4751 << 487.17  //   47.000      47.350
+                            << 167322.8346 << 487.17  //   51.000      51.413
+                            << 232939.6325 << 386.37  //   71.000      71.802
+                            << 278385.8268 << 336.50 //   84.852      86.000
+                            << 298556.40   << 336.50; //               91.000 - First layer in high altitude regime 
 
   LapseRateVector.resize(StdAtmosTemperatureTable->GetNumRows()-1);
   PressureBreakpointVector.resize(StdAtmosTemperatureTable->GetNumRows());
@@ -143,10 +156,11 @@ double FGStandardAtmosphere::GetPressure(double altitude) const
   // Iterate through the altitudes to find the current Base Altitude
   // in the table. That is, if the current altitude (the argument passed in)
   // is 20000 ft, then the base altitude from the table is 0.0. If the
-  // passed-in altitude is 40000 ft, the base altitude is 36151.6 ft (and
+  // passed-in altitude is 40000 ft, the base altitude is 36089.2388 ft (and
   // the index "b" is 2 - the second entry in the table).
   double testAlt = (*StdAtmosTemperatureTable)(b+1,0);
-  while ((altitude >= testAlt) && (b <= numRows-2)) {
+  double GeoPotAlt = (altitude*20855531.5)/(20855531.5+altitude);
+  while ((GeoPotAlt >= testAlt) && (b <= numRows-2)) {
     b++;
     testAlt = (*StdAtmosTemperatureTable)(b+1,0);
   }
@@ -154,7 +168,7 @@ double FGStandardAtmosphere::GetPressure(double altitude) const
 
   double BaseAlt = (*StdAtmosTemperatureTable)(b+1,0);
   Tmb = GetTemperature(BaseAlt);
-  deltaH = altitude - BaseAlt;
+  deltaH = GeoPotAlt - BaseAlt;
 
   if (LapseRateVector[b] != 0.00) {
     Lmb = LapseRateVector[b];
@@ -184,7 +198,9 @@ void FGStandardAtmosphere::SetPressureSL(ePressure unit, double pressure)
 
 double FGStandardAtmosphere::GetTemperature(double altitude) const
 {
-  double T = StdAtmosTemperatureTable->GetValue(altitude) + TemperatureBias;
+  double GeoPotAlt = (altitude*20855531.5)/(20855531.5+altitude);
+
+  double T = StdAtmosTemperatureTable->GetValue(GeoPotAlt) + TemperatureBias;
   if (altitude <= GradientFadeoutAltitude)
     T += TemperatureDeltaGradient * (GradientFadeoutAltitude - altitude);
 
@@ -202,7 +218,8 @@ double FGStandardAtmosphere::GetStdTemperature(double altitude) const
 
   if (altitude < 298556.4) {                // 91 km - station 8
 
-    temp = StdAtmosTemperatureTable->GetValue(altitude);
+    double GeoPotAlt = (altitude*20855531.5)/(20855531.5+altitude);
+    temp = StdAtmosTemperatureTable->GetValue(GeoPotAlt);
 
   } else if (altitude < 360892.4) {        // 110 km - station 9
 
index 18237ce7ada4ebbb011188f1cbf223b83bbd4aa4..e6fedc1031ba4f42de41d0a68fd68c7da09990d0 100644 (file)
@@ -51,7 +51,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGWinds.cpp,v 1.11 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGWinds.cpp,v 1.12 2014/02/17 05:02:38 jberndt Exp $");
 IDENT(IdHdr,ID_WINDS);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -76,7 +76,7 @@ FGWinds::FGWinds(FGFDMExec* fdmex) : FGModel(fdmex)
 {
   Name = "FGWinds";
 
-  MagnitudedAccelDt = MagnitudeAccel = Magnitude = 0.0;
+  MagnitudedAccelDt = MagnitudeAccel = Magnitude = TurbDirection = 0.0;
   SetTurbType( ttMilspec );
   TurbGain = 1.0;
   TurbRate = 10.0;
@@ -213,18 +213,18 @@ void FGWinds::Turbulence(double h)
     // max vertical wind speed in fps, corresponds to TurbGain = 1.0
     double max_vs = 40;
 
-    vTurbulenceNED(1) = vTurbulenceNED(2) = vTurbulenceNED(3) = 0.0;
+    vTurbulenceNED.InitMatrix();
     double delta = strength * max_vs * TurbGain * (1-Rhythmicity) * spike;
 
     // Vertical component of turbulence.
-    vTurbulenceNED(3) = sinewave * max_vs * TurbGain * Rhythmicity;
-    vTurbulenceNED(3)+= delta;
+    vTurbulenceNED(eDown) = sinewave * max_vs * TurbGain * Rhythmicity;
+    vTurbulenceNED(eDown)+= delta;
     if (in.DistanceAGL/in.wingspan < 3.0)
-        vTurbulenceNED(3) *= in.DistanceAGL/in.wingspan * 0.3333;
+        vTurbulenceNED(eDown) *= in.DistanceAGL/in.wingspan * 0.3333;
 
     // Yaw component of turbulence.
-    vTurbulenceNED(1) = sin( delta * 3.0 );
-    vTurbulenceNED(2) = cos( delta * 3.0 );
+    vTurbulenceNED(eNorth) = sin( delta * 3.0 );
+    vTurbulenceNED(eEast) = cos( delta * 3.0 );
 
     // Roll component of turbulence. Clockwise vortex causes left roll.
     vTurbPQR(eP) += delta * 0.04;
@@ -238,8 +238,8 @@ void FGWinds::Turbulence(double h)
     // an index of zero means turbulence is disabled
     // airspeed occurs as divisor in the code below
     if (probability_of_exceedence_index == 0 || in.V == 0) {
-      vTurbulenceNED(1) = vTurbulenceNED(2) = vTurbulenceNED(3) = 0.0;
-      vTurbPQR(1) = vTurbPQR(2) = vTurbPQR(3) = 0.0;
+      vTurbulenceNED(eNorth) = vTurbulenceNED(eEast) = vTurbulenceNED(eDown) = 0.0;
+      vTurbPQR(eP) = vTurbPQR(eQ) = vTurbPQR(eR) = 0.0;
       return;
     }
 
@@ -344,13 +344,13 @@ void FGWinds::Turbulence(double h)
 
     // rotate by wind azimuth and assign the velocities
     double cospsi = cos(psiw), sinpsi = sin(psiw);
-    vTurbulenceNED(1) =  cospsi*xi_u + sinpsi*xi_v;
-    vTurbulenceNED(2) = -sinpsi*xi_u + cospsi*xi_v;
-    vTurbulenceNED(3) = xi_w;
+    vTurbulenceNED(eNorth) =  cospsi*xi_u + sinpsi*xi_v;
+    vTurbulenceNED(eEast) = -sinpsi*xi_u + cospsi*xi_v;
+    vTurbulenceNED(eDown) = xi_w;
 
-    vTurbPQR(1) =  cospsi*xi_p + sinpsi*xi_q;
-    vTurbPQR(2) = -sinpsi*xi_p + cospsi*xi_q;
-    vTurbPQR(3) = xi_r;
+    vTurbPQR(eP) =  cospsi*xi_p + sinpsi*xi_q;
+    vTurbPQR(eQ) = -sinpsi*xi_p + cospsi*xi_q;
+    vTurbPQR(eR) = xi_r;
 
     // vTurbPQR is in the body fixed frame, not NED
     vTurbPQR = in.Tl2b*vTurbPQR;
@@ -367,6 +367,9 @@ void FGWinds::Turbulence(double h)
   default:
     break;
   }
+
+  TurbDirection = atan2( vTurbulenceNED(eEast), vTurbulenceNED(eNorth))*radtodeg;
+
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index fac8338e53cab228b9afc9833fe00751599e9298..522c497dc6f761dcdeb2b9177c4e3a5f5d3022e0 100644 (file)
@@ -47,7 +47,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_WINDS "$Id: FGWinds.h,v 1.9 2011/11/19 14:14:57 bcoconni Exp $"
+#define ID_WINDS "$Id: FGWinds.h,v 1.10 2014/02/17 05:02:38 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -210,8 +210,8 @@ public:
   virtual double GetRhythmicity() const {return Rhythmicity;}
 
   virtual double GetTurbPQR(int idx) const {return vTurbPQR(idx);}
-  virtual double GetTurbMagnitude(void) const {return Magnitude;}
-  virtual const FGColumnVector3& GetTurbDirection(void) const {return vDirection;}
+  virtual double GetTurbMagnitude(void) const {return vTurbulenceNED.Magnitude();}
+  virtual double GetTurbDirection(void) const {return TurbDirection;}
   virtual const FGColumnVector3& GetTurbPQR(void) const {return vTurbPQR;}
 
   virtual void   SetWindspeed20ft(double ws) { windspeed_at_20ft = ws;}
@@ -318,16 +318,13 @@ public:
 
 private:
 
-  double MagnitudedAccelDt, MagnitudeAccel, Magnitude;
+  double MagnitudedAccelDt, MagnitudeAccel, Magnitude, TurbDirection;
   double h;
   double TurbGain;
   double TurbRate;
   double Rhythmicity;
   double wind_from_clockwise;
   double spike, target_time, strength;
-  FGColumnVector3 vDirectiondAccelDt;
-  FGColumnVector3 vDirectionAccel;
-  FGColumnVector3 vDirection;
   FGColumnVector3 vTurbulenceGrad;
   FGColumnVector3 vBodyTurbGrad;
   FGColumnVector3 vTurbPQR;
index e917e3aca3c295549cda773681061a236e410a6a..33362c7388745569e10e159b9b62ff30dbc4377c 100644 (file)
@@ -44,7 +44,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGActuator.cpp,v 1.32 2014/01/13 10:46:07 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGActuator.cpp,v 1.33 2014/05/17 15:05:27 jberndt Exp $");
 IDENT(IdHdr,ID_ACTUATOR);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -173,6 +173,7 @@ bool FGActuator::Run(void )
     if (deadband_width != 0.0)   Deadband();
     if (hysteresis_width != 0.0) Hysteresis();
     if (bias != 0.0)             Bias();       // models a finite bias
+    if (delay != 0)              Delay();      // Model transport latency
   }
 
   PreviousOutput = Output; // previous value needed for "stuck" malfunction
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
index a78a3db..a136fa8
@@ -48,7 +48,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGDistributor.cpp,v 1.5 2014/01/13 10:46:08 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGDistributor.cpp,v 1.6 2014/02/17 05:33:25 jberndt Exp $");
 IDENT(IdHdr,ID_DISTRIBUTOR);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -152,7 +152,22 @@ void FGDistributor::Debug(int from)
 
   if (debug_lvl & 1) { // Standard console startup message output
     if (from == 0) { // Constructor
-
+      for (unsigned int ctr=0; ctr < Cases.size(); ctr++) {
+        std::cout << "      Case: " << ctr << endl;
+        if (Cases[ctr]->GetTest() != 0) {
+          Cases[ctr]->GetTest()->PrintCondition("        ");
+        } else {
+          std::cout << "        Set these properties by default: " << std::endl;
+        }
+        std::cout << std::endl;
+        for (unsigned int propCtr=0; propCtr < Cases[ctr]->GetNumPropValPairs(); propCtr++) {
+          std::cout << "        Set property " << Cases[ctr]->GetPropValPair(propCtr)->GetPropName();
+          if (Cases[ctr]->GetPropValPair(propCtr)->GetPropNode() == 0) std::cout << " (late bound)";
+          std::cout << " to " << Cases[ctr]->GetPropValPair(propCtr)->GetValString();
+          if (Cases[ctr]->GetPropValPair(propCtr)->GetLateBoundValue()) std::cout << " (late bound)";
+          std::cout << std::endl;
+        }
+      }
     }
   }
   if (debug_lvl & 2 ) { // Instantiation/Destruction notification
old mode 100755 (executable)
new mode 100644 (file)
index 55f8c7a..7946e37
@@ -49,7 +49,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_DISTRIBUTOR "$Id: FGDistributor.h,v 1.5 2013/11/24 11:40:57 bcoconni Exp $"
+#define ID_DISTRIBUTOR "$Id: FGDistributor.h,v 1.6 2014/02/17 05:33:25 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -99,7 +99,7 @@ Here's an example:
 Note: In the "logic" attribute, "AND" is the default logic, if none is supplied.
 
 @author Jon S. Berndt
-@version $Id: FGDistributor.h,v 1.5 2013/11/24 11:40:57 bcoconni Exp $
+@version $Id: FGDistributor.h,v 1.6 2014/02/17 05:33:25 jberndt Exp $
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -129,14 +129,18 @@ private:
   class PropValPair {
   public:
     PropValPair(std::string prop, std::string val, FGPropertyManager* propMan) {
+      // Process property to be set
       PropMan = propMan;
       sign = 1;
-      Val = 0;
-      ValString = val;
       FGPropertyNode *node = propMan->GetNode(prop, false);
       if (node) PropNode = node;
       else PropNode = 0;
       PropName = prop;
+
+      // Process set value
+      LateBoundValue = false;
+      Val = 0;
+      ValString = val;
       if (is_number(ValString)) {
         Val = new FGRealValue(atof(ValString.c_str()));
       } else {
@@ -145,8 +149,12 @@ private:
           sign = -1;
           ValString.erase(0,1);
         }
-        node = propMan->GetNode(ValString, false);
+        node = propMan->GetNode(ValString, false); // Reuse the node variable
         if (node) Val = new FGPropertyValue(node);
+        else {
+          Val = new FGPropertyValue(ValString, propMan);
+          LateBoundValue = true;
+        }
       }
     }
 
@@ -163,23 +171,20 @@ private:
           throw(PropName+" in distributor component is not known");
         }
       }
-      if (Val == 0) {
-        if (PropMan->HasNode(ValString)) {
-          FGPropertyNode* node = PropMan->GetNode(ValString, false);
-          if (node) Val = new FGPropertyValue(node);
-        } else {
-          throw(ValString+" in distributor component is not known. Check spelling.");
-        }
-      }
       PropNode->setDoubleValue(Val->GetValue()*sign);
     }
 
+    std::string GetPropName() {return PropName;}
+    std::string GetValString() {return ValString;}
+    FGPropertyNode* GetPropNode() {return PropNode;}
+    bool GetLateBoundValue() {return LateBoundValue;}
   private:
     std::string PropName;
     FGPropertyNode* PropNode;
     FGPropertyManager* PropMan;
     FGParameter* Val;
     std::string ValString;
+    bool LateBoundValue;
     int sign;
   };
 
@@ -195,10 +200,13 @@ private:
     }
 
     void SetTest(FGCondition* test) {Test = test;}
+    FGCondition* GetTest(void) {return Test;}
     void AddPropValPair(PropValPair* pvPair) {PropValPairs.push_back(pvPair);}
     void SetPropValPairs() {
       for (unsigned int i=0; i<PropValPairs.size(); i++) PropValPairs[i]->SetPropToValue();
     }
+    PropValPair* GetPropValPair(unsigned int idx) { return PropValPairs[idx]; }
+    unsigned int GetNumPropValPairs(void) {return PropValPairs.size();}
     bool HasTest() {return (Test != 0);}
     bool GetTestResult() { return Test->Evaluate(); }
 
index 7ccaebf26fe1d7d1fa4c9d47902bfdb43e79d676..4e1680a9554187e2734ca4ab44d1c2abcf6bd045 100644 (file)
@@ -46,7 +46,7 @@ INCLUDES
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_FCSCOMPONENT "$Id: FGFCSComponent.h,v 1.25 2014/01/02 21:58:42 bcoconni Exp $"
+#define ID_FCSCOMPONENT "$Id: FGFCSComponent.h,v 1.26 2014/02/17 05:33:25 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -78,11 +78,11 @@ CLASS DOCUMENTATION
     - FGAccelerometer
     - FGGyro
     - FGActuator
-    - FGWaypoint
+    - FGWwaypoint
     - FGAngle
 
     @author Jon S. Berndt
-    @version $Id: FGFCSComponent.h,v 1.25 2014/01/02 21:58:42 bcoconni Exp $
+    @version $Id: FGFCSComponent.h,v 1.26 2014/02/17 05:33:25 jberndt Exp $
     @see Documentation for the FGFCS class, and for the configuration file class
 */
 
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
old mode 100755 (executable)
new mode 100644 (file)
index c7310b734dd20fe592d66fad9d7d579a6b05bbf7..230e7483d8f2fbe6c10bdecaa2ef6c610f99f8b4 100644 (file)
@@ -49,7 +49,7 @@ using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGRocket.cpp,v 1.33 2014/01/13 10:46:10 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGRocket.cpp,v 1.35 2014/05/17 15:04:14 jberndt Exp $");
 IDENT(IdHdr,ID_ROCKET);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -254,6 +254,12 @@ string FGRocket::GetEngineLabels(const string& delimiter)
 
   buf << Name << " Total Impulse (engine " << EngineNumber << " in lbf)" << delimiter
       << Name << " Total Vacuum Impulse (engine " << EngineNumber << " in lbf)" << delimiter
+      << Name << " Roll Moment (engine " << EngineNumber << " in ft-lbf)" << delimiter
+      << Name << " Pitch Moment (engine " << EngineNumber << " in ft-lbf)" << delimiter
+      << Name << " Yaw Moment (engine " << EngineNumber << " in ft-lbf)" << delimiter
+      << Name << " X Force (engine " << EngineNumber << " in lbf)" << delimiter
+      << Name << " Y Force (engine " << EngineNumber << " in lbf)" << delimiter
+      << Name << " Z Force (engine " << EngineNumber << " in lbf)" << delimiter
       << Thruster->GetThrusterLabels(EngineNumber, delimiter);
 
   return buf.str();
@@ -267,6 +273,8 @@ string FGRocket::GetEngineValues(const string& delimiter)
 
   buf << It << delimiter 
       << ItVac << delimiter 
+      << GetMoments().Dump(delimiter) << delimiter
+      << Thruster->GetBodyForces().Dump(delimiter) << delimiter
       << Thruster->GetThrusterValues(EngineNumber, delimiter);
 
   return buf.str();
@@ -283,6 +291,8 @@ void FGRocket::bindmodel()
 
   property_name = base_property_name + "/total-impulse";
   PropertyManager->Tie( property_name.c_str(), this, &FGRocket::GetTotalImpulse);
+  property_name = base_property_name + "/total-vac-impulse";
+  PropertyManager->Tie( property_name.c_str(), this, &FGRocket::GetVacTotalImpulse);
   property_name = base_property_name + "/vacuum-thrust_lbs";
   PropertyManager->Tie( property_name.c_str(), this, &FGRocket::GetVacThrust);
 
index 95829d3c487d46943728fc7efbdf5b5f623f3952..de5b195907f8b7a280065abb52789309101e9fa3 100644 (file)
@@ -36,18 +36,19 @@ HISTORY
 INCLUDES
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
+#include <cstdlib>
+#include <iostream>
 #include "FGTank.h"
 #include "FGFDMExec.h"
 #include "input_output/FGXMLElement.h"
 #include "input_output/FGPropertyManager.h"
-#include <iostream>
-#include <cstdlib>
+#include "input_output/string_utilities.h"
 
 using namespace std;
 
 namespace JSBSim {
 
-IDENT(IdSrc,"$Id: FGTank.cpp,v 1.39 2014/01/13 10:46:10 ehofman Exp $");
+IDENT(IdSrc,"$Id: FGTank.cpp,v 1.40 2014/05/17 15:09:42 jberndt Exp $");
 IDENT(IdHdr,ID_TANK);
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -74,6 +75,7 @@ FGTank::FGTank(FGFDMExec* exec, Element* el, int tank_number)
   PropertyManager = Exec->GetPropertyManager();
   vXYZ.InitMatrix();
   vXYZ_drain.InitMatrix();
+  ixx_unit = iyy_unit = izz_unit = 1.0;
 
   type = el->GetAttributeValue("type");
   if      (type == "FUEL")     Type = ttFUEL;
@@ -127,6 +129,27 @@ FGTank::FGTank(FGFDMExec* exec, Element* el, int tank_number)
 
   PctFull = 100.0*Contents/Capacity;            // percent full; 0 to 100.0
 
+  string property_name, base_property_name;
+  base_property_name = CreateIndexedPropertyName("propulsion/tank", TankNumber);
+  property_name = base_property_name + "/contents-lbs";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetContents,
+                                       &FGTank::SetContents );
+  property_name = base_property_name + "/pct-full";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetPctFull);
+
+  property_name = base_property_name + "/priority";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetPriority,
+                                       &FGTank::SetPriority );
+  property_name = base_property_name + "/external-flow-rate-pps";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetExternalFlow,
+                                       &FGTank::SetExternalFlow );
+  property_name = base_property_name + "/local-ixx-slug_ft2";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetIxx);
+  property_name = base_property_name + "/local-iyy-slug_ft2";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetIyy);
+  property_name = base_property_name + "/local-izz-slug_ft2";
+  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetIzz);
+
   // Check whether this is a solid propellant "tank". Initialize it if true.
 
   grainType = gtUNKNOWN; // This is the default
@@ -137,6 +160,38 @@ FGTank::FGTank(FGFDMExec* exec, Element* el, int tank_number)
     strGType = element_Grain->GetAttributeValue("type");
     if (strGType == "CYLINDRICAL")     grainType = gtCYLINDRICAL;
     else if (strGType == "ENDBURNING") grainType = gtENDBURNING;
+    else if (strGType == "FUNCTION")   {
+      grainType = gtFUNCTION;
+      if (element_Grain->FindElement("ixx") != 0) {
+        Element* element_ixx = element_Grain->FindElement("ixx");
+        if (element_ixx->GetAttributeValue("unit") == "KG*M2") ixx_unit = 1.0/1.35594;
+        if (element_ixx->FindElement("function") != 0) {
+          function_ixx = new FGFunction(PropertyManager, element_ixx->FindElement("function"));
+        }
+      } else {
+        throw("For tank "+to_string(TankNumber)+" and when grain_config is specified an ixx must be specified when the FUNCTION grain type is specified.");
+      }
+
+      if (element_Grain->FindElement("iyy")) {
+        Element* element_iyy = element_Grain->FindElement("iyy");
+        if (element_iyy->GetAttributeValue("unit") == "KG*M2") iyy_unit = 1.0/1.35594;
+        if (element_iyy->FindElement("function") != 0) {
+          function_iyy = new FGFunction(PropertyManager, element_iyy->FindElement("function"));
+        }
+      } else {
+        throw("For tank "+to_string(TankNumber)+" and when grain_config is specified an iyy must be specified when the FUNCTION grain type is specified.");
+      }
+
+      if (element_Grain->FindElement("izz")) {
+        Element* element_izz = element_Grain->FindElement("izz");
+        if (element_izz->GetAttributeValue("unit") == "KG*M2") izz_unit = 1.0/1.35594;
+        if (element_izz->FindElement("function") != 0) {
+          function_izz = new FGFunction(PropertyManager, element_izz->FindElement("function"));
+        }
+      } else {
+        throw("For tank "+to_string(TankNumber)+" and when grain_config is specified an izz must be specified when the FUNCTION grain type is specified.");
+      }
+    }
     else                               cerr << "Unknown propellant grain type specified" << endl;
 
     if (element_Grain->FindElement("length"))
@@ -157,6 +212,9 @@ FGTank::FGTank(FGFDMExec* exec, Element* el, int tank_number)
       case gtENDBURNING:
         Volume = M_PI * Length * Radius * Radius; // cubic inches
         break;
+      case gtFUNCTION:
+        Volume = 1;  // Volume is irrelevant for the FUNCTION type, but it can't be zero!
+        break;
       case gtUNKNOWN:
         cerr << "Unknown grain type found in this rocket engine definition." << endl;
         exit(-1);
@@ -166,21 +224,6 @@ FGTank::FGTank(FGFDMExec* exec, Element* el, int tank_number)
 
     CalculateInertias();
 
-  string property_name, base_property_name;
-  base_property_name = CreateIndexedPropertyName("propulsion/tank", TankNumber);
-  property_name = base_property_name + "/contents-lbs";
-  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetContents,
-                                       &FGTank::SetContents );
-  property_name = base_property_name + "/pct-full";
-  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetPctFull);
-
-  property_name = base_property_name + "/priority";
-  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetPriority,
-                                       &FGTank::SetPriority );
-  property_name = base_property_name + "/external-flow-rate-pps";
-  PropertyManager->Tie( property_name.c_str(), (FGTank*)this, &FGTank::GetExternalFlow,
-                                       &FGTank::SetExternalFlow );
-
   if (Temperature != -9999.0)  InitialTemperature = Temperature = FahrenheitToCelsius(Temperature);
   Area = 40.0 * pow(Capacity/1975, 0.666666667);
 
@@ -344,20 +387,26 @@ void FGTank::CalculateInertias(void)
       RadSumSqr = (Rad2 + InnerRadius*InnerRadius)/144.0;
       Ixx = 0.5*Mass*RadSumSqr;
       Iyy = Mass*(3.0*RadSumSqr + Length*Length/144.0)/12.0;
+        Izz  = Iyy;
       break;
     case gtENDBURNING:
       Length = Volume/(M_PI*Rad2);
       Ixx = 0.5*Mass*Rad2/144.0;
       Iyy = Mass*(3.0*Rad2 + Length*Length)/(144.0*12.0);
+        Izz  = Iyy;
       break;
+      case gtFUNCTION:
+        Ixx = function_ixx->GetValue()*ixx_unit;
+        Iyy = function_iyy->GetValue()*iyy_unit;
+        Izz = function_izz->GetValue()*izz_unit;
+        break;
     case gtUNKNOWN:
       cerr << "Unknown grain type found." << endl;
       exit(-1);
       break;
   }
-  Izz  = Iyy;
 
-  } else { // assume liquid propellant
+  } else { // assume liquid propellant: shrinking snowball
 
     if (Radius > 0.0) Ixx = Iyy = Izz = Mass * InertiaFactor * 0.4 * Radius * Radius / 144.0;
 
index fc9532f86debea5f650ac7b4ce24c42d660d9ccc..00bc9b6ae9a8963fe36652187a50129d998bb608 100644 (file)
@@ -46,13 +46,14 @@ INCLUDES
 
 #include "FGJSBBase.h"
 #include "math/FGColumnVector3.h"
+#include "math/FGFunction.h"
 #include <string>
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#define ID_TANK "$Id: FGTank.h,v 1.27 2012/08/11 14:57:38 jberndt Exp $"
+#define ID_TANK "$Id: FGTank.h,v 1.28 2014/05/17 15:09:42 jberndt Exp $"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 FORWARD DECLARATIONS
@@ -115,8 +116,12 @@ CLASS DOCUMENTATION
 
 @code
 <tank type="{FUEL | OXIDIZER}">
-  <grain_config type="{CYLINDRICAL | ENDBURNING}">
-    <length unit="{IN | FT | M}"> {number} </radius>
+  <grain_config type="{CYLINDRICAL | ENDBURNING | FUNCTION}">
+    <length unit="{IN | FT | M}"> {number} </length>
+    <bore_diameter unit="{IN | FT | M}"> {number} </bore_diameter>
+    [<ixx unit="{IN | FT | M}"> {function} </ixx>
+    <iyy unit="{IN | FT | M}"> {function} </iyy>
+    <izz unit="{IN | FT | M}"> {function} </izz>]
   </grain_config>
   <location unit="{FT | M | IN}">
     <x> {number} </x>
@@ -205,7 +210,7 @@ public:
   ~FGTank();
 
   enum TankType {ttUNKNOWN, ttFUEL, ttOXIDIZER};
-  enum GrainType {gtUNKNOWN, gtCYLINDRICAL, gtENDBURNING};
+  enum GrainType {gtUNKNOWN, gtCYLINDRICAL, gtENDBURNING, gtFUNCTION};
 
   /** Removes fuel from the tank.
       This function removes fuel from a tank. If the tank empties, it is
@@ -306,8 +311,14 @@ private:
   int TankNumber;
   std::string type;
   std::string strGType;
+  double ixx_unit;
+  double iyy_unit;
+  double izz_unit;
   FGColumnVector3 vXYZ;
   FGColumnVector3 vXYZ_drain;
+  FGFunction* function_ixx;
+  FGFunction* function_iyy;
+  FGFunction* function_izz;
   double Capacity;
   double Radius;
   double InnerRadius;
old mode 100755 (executable)
new mode 100644 (file)