]> git.mxchange.org Git - flightgear.git/commitdiff
Update to the latest version of JSBSim which supports Lighter Than Air craft
authorehofman <ehofman>
Thu, 10 Jul 2008 17:23:02 +0000 (17:23 +0000)
committerehofman <ehofman>
Thu, 10 Jul 2008 17:23:02 +0000 (17:23 +0000)
(like Airships) and external forces.

111 files changed:
src/FDM/JSBSim/FGFDMExec.cpp
src/FDM/JSBSim/FGFDMExec.h
src/FDM/JSBSim/FGJSBBase.cpp
src/FDM/JSBSim/FGJSBBase.h
src/FDM/JSBSim/FGState.cpp
src/FDM/JSBSim/FGState.h
src/FDM/JSBSim/JSBSim.cxx
src/FDM/JSBSim/JSBSim.hxx
src/FDM/JSBSim/initialization/FGInitialCondition.cpp
src/FDM/JSBSim/initialization/FGInitialCondition.h
src/FDM/JSBSim/initialization/FGTrim.cpp
src/FDM/JSBSim/input_output/FGGroundCallback.cpp
src/FDM/JSBSim/input_output/FGGroundCallback.h
src/FDM/JSBSim/input_output/FGPropertyManager.cpp
src/FDM/JSBSim/input_output/FGPropertyManager.h
src/FDM/JSBSim/input_output/FGScript.cpp
src/FDM/JSBSim/input_output/FGScript.h
src/FDM/JSBSim/input_output/FGXMLElement.cpp
src/FDM/JSBSim/input_output/FGXMLElement.h
src/FDM/JSBSim/input_output/FGfdmSocket.cpp
src/FDM/JSBSim/input_output/FGfdmSocket.h
src/FDM/JSBSim/input_output/net_fdm.hxx [new file with mode: 0644]
src/FDM/JSBSim/math/FGColumnVector3.h
src/FDM/JSBSim/math/FGCondition.cpp
src/FDM/JSBSim/math/FGCondition.h
src/FDM/JSBSim/math/FGFunction.cpp
src/FDM/JSBSim/math/FGFunction.h
src/FDM/JSBSim/math/FGLocation.cpp
src/FDM/JSBSim/math/FGLocation.h
src/FDM/JSBSim/math/FGMatrix33.h
src/FDM/JSBSim/math/FGQuaternion.cpp
src/FDM/JSBSim/math/FGQuaternion.h
src/FDM/JSBSim/math/FGTable.cpp
src/FDM/JSBSim/models/FGAerodynamics.cpp
src/FDM/JSBSim/models/FGAerodynamics.h
src/FDM/JSBSim/models/FGAircraft.cpp
src/FDM/JSBSim/models/FGAircraft.h
src/FDM/JSBSim/models/FGAtmosphere.cpp
src/FDM/JSBSim/models/FGAtmosphere.h
src/FDM/JSBSim/models/FGAuxiliary.cpp
src/FDM/JSBSim/models/FGAuxiliary.h
src/FDM/JSBSim/models/FGBuoyantForces.cpp [new file with mode: 0644]
src/FDM/JSBSim/models/FGBuoyantForces.h [new file with mode: 0644]
src/FDM/JSBSim/models/FGExternalForce.cpp [new file with mode: 0755]
src/FDM/JSBSim/models/FGExternalForce.h [new file with mode: 0755]
src/FDM/JSBSim/models/FGExternalReactions.cpp [new file with mode: 0755]
src/FDM/JSBSim/models/FGExternalReactions.h [new file with mode: 0755]
src/FDM/JSBSim/models/FGFCS.cpp
src/FDM/JSBSim/models/FGFCS.h
src/FDM/JSBSim/models/FGGasCell.cpp [new file with mode: 0644]
src/FDM/JSBSim/models/FGGasCell.h [new file with mode: 0644]
src/FDM/JSBSim/models/FGGroundReactions.cpp
src/FDM/JSBSim/models/FGGroundReactions.h
src/FDM/JSBSim/models/FGInertial.cpp
src/FDM/JSBSim/models/FGInertial.h
src/FDM/JSBSim/models/FGInput.cpp
src/FDM/JSBSim/models/FGInput.h
src/FDM/JSBSim/models/FGLGear.cpp
src/FDM/JSBSim/models/FGLGear.h
src/FDM/JSBSim/models/FGMassBalance.cpp
src/FDM/JSBSim/models/FGMassBalance.h
src/FDM/JSBSim/models/FGModel.cpp
src/FDM/JSBSim/models/FGModel.h
src/FDM/JSBSim/models/FGOutput.cpp
src/FDM/JSBSim/models/FGOutput.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/Makefile.am
src/FDM/JSBSim/models/atmosphere/FGMSIS.cpp
src/FDM/JSBSim/models/atmosphere/FGMars.cpp
src/FDM/JSBSim/models/flight_control/FGActuator.cpp
src/FDM/JSBSim/models/flight_control/FGActuator.h
src/FDM/JSBSim/models/flight_control/FGDeadBand.cpp
src/FDM/JSBSim/models/flight_control/FGDeadBand.h
src/FDM/JSBSim/models/flight_control/FGFCSComponent.cpp
src/FDM/JSBSim/models/flight_control/FGFCSFunction.cpp
src/FDM/JSBSim/models/flight_control/FGFCSFunction.h
src/FDM/JSBSim/models/flight_control/FGFilter.cpp
src/FDM/JSBSim/models/flight_control/FGFilter.h
src/FDM/JSBSim/models/flight_control/FGGain.cpp
src/FDM/JSBSim/models/flight_control/FGGain.h
src/FDM/JSBSim/models/flight_control/FGKinemat.h
src/FDM/JSBSim/models/flight_control/FGPID.cpp
src/FDM/JSBSim/models/flight_control/FGPID.h
src/FDM/JSBSim/models/flight_control/FGSensor.cpp
src/FDM/JSBSim/models/flight_control/FGSensor.h
src/FDM/JSBSim/models/flight_control/FGSummer.cpp
src/FDM/JSBSim/models/flight_control/FGSummer.h
src/FDM/JSBSim/models/flight_control/FGSwitch.cpp
src/FDM/JSBSim/models/flight_control/FGSwitch.h
src/FDM/JSBSim/models/propulsion/FGElectric.h
src/FDM/JSBSim/models/propulsion/FGEngine.cpp
src/FDM/JSBSim/models/propulsion/FGEngine.h
src/FDM/JSBSim/models/propulsion/FGForce.cpp
src/FDM/JSBSim/models/propulsion/FGForce.h
src/FDM/JSBSim/models/propulsion/FGNozzle.h
src/FDM/JSBSim/models/propulsion/FGPiston.cpp
src/FDM/JSBSim/models/propulsion/FGPiston.h
src/FDM/JSBSim/models/propulsion/FGPropeller.cpp
src/FDM/JSBSim/models/propulsion/FGPropeller.h
src/FDM/JSBSim/models/propulsion/FGRocket.h
src/FDM/JSBSim/models/propulsion/FGTank.cpp
src/FDM/JSBSim/models/propulsion/FGTank.h
src/FDM/JSBSim/models/propulsion/FGThruster.cpp
src/FDM/JSBSim/models/propulsion/FGThruster.h
src/FDM/JSBSim/models/propulsion/FGTurbine.cpp
src/FDM/JSBSim/models/propulsion/FGTurbine.h
src/FDM/JSBSim/models/propulsion/FGTurboProp.cpp
src/FDM/JSBSim/models/propulsion/FGTurboProp.h

index 94088579a2e21b4c13c58eb25cf685e08aa1dc5f..5ed9ce5310a7561651d88f7b51b1935585db0754 100644 (file)
@@ -63,6 +63,8 @@ INCLUDES
 #include <models/FGPropulsion.h>
 #include <models/FGMassBalance.h>
 #include <models/FGGroundReactions.h>
+#include <models/FGExternalReactions.h>
+#include <models/FGBuoyantForces.h>
 #include <models/FGAerodynamics.h>
 #include <models/FGInertial.h>
 #include <models/FGAircraft.h>
@@ -71,6 +73,7 @@ INCLUDES
 #include <models/FGInput.h>
 #include <models/FGOutput.h>
 #include <initialization/FGInitialCondition.h>
+//#include <initialization/FGTrimAnalysis.h> // Remove until later
 #include <input_output/FGPropertyManager.h>
 #include <input_output/FGScript.h>
 
@@ -97,10 +100,11 @@ void checkTied ( FGPropertyManager *node )
 
   for (int i=0; i<N; i++) {
     if (node->getChild(i)->nChildren() ) {
+//      cout << "Untieing " << node->getChild(i)->getName() << " property branch." << endl;
       checkTied( (FGPropertyManager*)node->getChild(i) );
     } else if ( node->getChild(i)->isTied() ) {
       name = ((FGPropertyManager*)node->getChild(i))->GetFullyQualifiedName();
-      cerr << name << " is tied" << endl;
+      node->Untie(name);
     }
   }
 }
@@ -123,6 +127,8 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root) : Root(root)
   Aerodynamics    = 0;
   Inertial        = 0;
   GroundReactions = 0;
+  ExternalReactions = 0;
+  BuoyantForces   = 0;
   Aircraft        = 0;
   Propagate       = 0;
   Auxiliary       = 0;
@@ -153,10 +159,13 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root) : Root(root)
     debug_lvl = 1;
   }
 
-  if (Root == 0)  master= new FGPropertyManager;
-  else            master = Root;
+  if (Root == 0) {
+    if (master == 0)
+      master = new FGPropertyManager;
+    Root = master;
+  }
 
-  instance = master->GetNode("/fdm/jsbsim",IdFDM,true);
+  instance = Root->GetNode("/fdm/jsbsim",IdFDM,true);
   Debug(0);
   // this is to catch errors in binding member functions to the property tree.
   try {
@@ -166,9 +175,13 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root) : Root(root)
     exit(1);
   }
 
+  trim_status = false;
+  ta_mode     = 99;
+
   Constructing = true;
   typedef int (FGFDMExec::*iPMF)(void) const;
-  instance->Tie("simulation/do_trim", this, (iPMF)0, &FGFDMExec::DoTrim);
+//  instance->Tie("simulation/do_trim_analysis", this, (iPMF)0, &FGFDMExec::DoTrimAnalysis);
+  instance->Tie("simulation/do_simple_trim", this, (iPMF)0, &FGFDMExec::DoTrim);
   instance->Tie("simulation/terminate", (int *)&Terminate);
   Constructing = false;
 }
@@ -177,12 +190,9 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root) : Root(root)
 
 FGFDMExec::~FGFDMExec()
 {
-  instance->Untie("simulation/do_trim");
-  instance->Untie("simulation/terminate");
-
   try {
-    DeAllocate();
     checkTied( instance );
+    DeAllocate();
     if (Root == 0)  delete master;
   } catch ( string msg ) {
     cout << "Caught error: " << msg << endl;
@@ -208,54 +218,36 @@ bool FGFDMExec::Allocate(void)
   MassBalance     = new FGMassBalance(this);
   Aerodynamics    = new FGAerodynamics (this);
   Inertial        = new FGInertial(this);
+
+  GroundCallback  = new FGGroundCallback(Inertial->GetRefRadius());
+
   GroundReactions = new FGGroundReactions(this);
+  ExternalReactions = new FGExternalReactions(this);
+  BuoyantForces   = new FGBuoyantForces(this);
   Aircraft        = new FGAircraft(this);
   Propagate       = new FGPropagate(this);
   Auxiliary       = new FGAuxiliary(this);
   Input           = new FGInput(this);
 
-  GroundCallback  = new FGGroundCallback();
   State           = new FGState(this); // This must be done here, as the FGState
                                        // class needs valid pointers to the above
                                        // model classes
 
   // Initialize models so they can communicate with each other
 
-  if (!Atmosphere->InitModel()) {
-    cerr << fgred << "Atmosphere model init failed" << fgdef << endl;
-    Error+=1;}
-  if (!FCS->InitModel())        {
-    cerr << fgred << "FCS model init failed" << fgdef << endl;
-    Error+=2;}
-  if (!Propulsion->InitModel()) {
-    cerr << fgred << "FGPropulsion model init failed" << fgdef << endl;
-    Error+=4;}
-  if (!MassBalance->InitModel()) {
-    cerr << fgred << "FGMassBalance model init failed" << fgdef << endl;
-    Error+=8;}
-  if (!Aerodynamics->InitModel()) {
-    cerr << fgred << "FGAerodynamics model init failed" << fgdef << endl;
-    Error+=16;}
-  if (!Inertial->InitModel()) {
-    cerr << fgred << "FGInertial model init failed" << fgdef << endl;
-    Error+=32;}
-  if (!GroundReactions->InitModel())   {
-    cerr << fgred << "Ground Reactions model init failed" << fgdef << endl;
-    Error+=64;}
-  if (!Aircraft->InitModel())   {
-    cerr << fgred << "Aircraft model init failed" << fgdef << endl;
-    Error+=128;}
-  if (!Propagate->InitModel())   {
-    cerr << fgred << "Propagate model init failed" << fgdef << endl;
-    Error+=256;}
-  if (!Auxiliary->InitModel())  {
-    cerr << fgred << "Auxiliary model init failed" << fgdef << endl;
-    Error+=512;}
-  if (!Input->InitModel())  {
-    cerr << fgred << "Input model init failed" << fgdef << endl;
-    Error+=1024;}
-
-  if (Error > 0) result = false;
+  Atmosphere->InitModel();
+  FCS->InitModel();
+  Propulsion->InitModel();
+  MassBalance->InitModel();
+  Aerodynamics->InitModel();
+  Inertial->InitModel();
+  GroundReactions->InitModel();
+  ExternalReactions->InitModel();
+  BuoyantForces->InitModel();
+  Aircraft->InitModel();
+  Propagate->InitModel();
+  Auxiliary->InitModel();
+  Input->InitModel();
 
   IC = new FGInitialCondition(this);
 
@@ -271,6 +263,8 @@ bool FGFDMExec::Allocate(void)
   Schedule(Aerodynamics,    1);
   Schedule(Inertial,        1);
   Schedule(GroundReactions, 1);
+  Schedule(ExternalReactions, 1);
+  Schedule(BuoyantForces,   1);
   Schedule(Aircraft,        1);
   Schedule(Propagate,       1);
   Schedule(Auxiliary,       1);
@@ -292,6 +286,8 @@ bool FGFDMExec::DeAllocate(void)
   delete Aerodynamics;
   delete Inertial;
   delete GroundReactions;
+  delete ExternalReactions;
+  delete BuoyantForces;
   delete Aircraft;
   delete Propagate;
   delete Auxiliary;
@@ -318,9 +314,12 @@ bool FGFDMExec::DeAllocate(void)
   Aerodynamics    = 0;
   Inertial        = 0;
   GroundReactions = 0;
+  ExternalReactions = 0;
+  BuoyantForces   = 0;
   Aircraft        = 0;
   Propagate       = 0;
   Auxiliary       = 0;
+  Script          = 0;
 
   modelLoaded = false;
   return modelLoaded;
@@ -357,7 +356,7 @@ int FGFDMExec::Schedule(FGModel* model, int rate)
 
 bool FGFDMExec::Run(void)
 {
-  bool success=false;
+  bool success=true;
   FGModel* model_iterator;
 
   model_iterator = FirstModel;
@@ -370,8 +369,10 @@ bool FGFDMExec::Run(void)
 //    SlaveFDMList[i]->exec->Run();
   }
 
-  if (Script != 0) success = Script->RunScript(); // returns true if success
-                                                  // false if complete
+  // returns true if success
+  // false if complete
+  if (Script != 0 && !State->IntegrationSuspended()) success = Script->RunScript();
+
   while (model_iterator != 0L) {
     model_iterator->Run();
     model_iterator = model_iterator->NextModel;
@@ -380,6 +381,7 @@ bool FGFDMExec::Run(void)
   Frame++;
   if (!Holding()) State->IncrTime();
   if (Terminate) success = false;
+
   return (success);
 }
 
@@ -398,6 +400,24 @@ bool FGFDMExec::RunIC(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGFDMExec::ResetToInitialConditions(void)
+{
+  FGModel* model_iterator;
+
+  model_iterator = FirstModel;
+  if (model_iterator == 0L) return;
+
+  while (model_iterator != 0L) {
+    model_iterator->InitModel();
+    model_iterator = model_iterator->NextModel;
+  }
+
+  RunIC();
+  if (Script) Script->ResetEvents();
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 void FGFDMExec::SetGroundCallback(FGGroundCallback* p)
 {
   delete GroundCallback;
@@ -447,11 +467,12 @@ bool FGFDMExec::LoadScript(string script)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-bool FGFDMExec::LoadModel(string AircraftPath, string EnginePath, string model,
-                bool addModelToPath)
+bool FGFDMExec::LoadModel(string AircraftPath, string EnginePath, string SystemsPath,
+                string model, bool addModelToPath)
 {
   FGFDMExec::AircraftPath = AircraftPath;
   FGFDMExec::EnginePath = EnginePath;
+  FGFDMExec::SystemsPath = SystemsPath;
 
   return LoadModel(model, addModelToPath);
 }
@@ -464,6 +485,7 @@ bool FGFDMExec::LoadModel(string model, bool addModelToPath)
   string aircraftCfgFileName;
   string separator = "/";
   Element* element = 0L;
+  bool result = false; // initialize result to false, indicating input file not yet read
 
   modelName = model; // Set the class modelName attribute
 
@@ -471,9 +493,9 @@ bool FGFDMExec::LoadModel(string model, bool addModelToPath)
     separator = ";";
 # endif
 
-  if( AircraftPath.empty() || EnginePath.empty() ) {
+  if( AircraftPath.empty() || EnginePath.empty() || SystemsPath.empty()) {
     cerr << "Error: attempted to load aircraft with undefined ";
-    cerr << "aircraft and engine paths" << endl;
+    cerr << "aircraft, engine, and system paths" << endl;
     return false;
   }
 
@@ -487,35 +509,48 @@ bool FGFDMExec::LoadModel(string model, bool addModelToPath)
   }
 
   document = LoadXMLDocument(aircraftCfgFileName); // "document" is a class member
-  ReadPrologue(document);
-  element = document->GetElement();
-
-  bool result = true;
-  while (element && result) {
-    string element_name = element->GetName();
-    if (element_name == "fileheader" )           result = ReadFileHeader(element);
-    else if (element_name == "slave")            result = ReadSlave(element);
-    else if (element_name == "metrics")          result = Aircraft->Load(element);
-    else if (element_name == "mass_balance")     result = MassBalance->Load(element);
-    else if (element_name == "ground_reactions") result = GroundReactions->Load(element);
-    else if (element_name == "propulsion")       result = Propulsion->Load(element);
-    else if (element_name == "autopilot")        result = FCS->Load(element);
-    else if (element_name == "flight_control")   result = FCS->Load(element);
-    else if (element_name == "aerodynamics")     result = Aerodynamics->Load(element);
-    else if (element_name == "input")            result = Input->Load(element);
-    else if (element_name == "output")           {
-        FGOutput* Output = new FGOutput(this);
-        Output->InitModel();
-        Schedule(Output,       1);
-        Outputs.push_back(Output);
-        result = Output->Load(element);
+  if (document) {
+    ReadPrologue(document);
+    element = document->GetElement();
+
+    result = true;
+    while (element && result) {
+      string element_name = element->GetName();
+      if (element_name == "fileheader" )           result = ReadFileHeader(element);
+      else if (element_name == "slave")            result = ReadSlave(element);
+      else if (element_name == "metrics")          result = Aircraft->Load(element);
+      else if (element_name == "mass_balance")     result = MassBalance->Load(element);
+      else if (element_name == "ground_reactions") result = GroundReactions->Load(element);
+      else if (element_name == "external_reactions") result = ExternalReactions->Load(element);
+      else if (element_name == "buoyant_forces")   result = BuoyantForces->Load(element);
+      else if (element_name == "propulsion")       result = Propulsion->Load(element);
+      else if (element_name == "system")           result = FCS->Load(element,
+                                                            FGFCS::stSystem);
+      else if (element_name == "autopilot")        result = FCS->Load(element,
+                                                            FGFCS::stAutoPilot);
+      else if (element_name == "flight_control")   result = FCS->Load(element,
+                                                            FGFCS::stFCS);
+      else if (element_name == "aerodynamics")     result = Aerodynamics->Load(element);
+      else if (element_name == "input")            result = Input->Load(element);
+      else if (element_name == "output")           {
+          FGOutput* Output = new FGOutput(this);
+          Output->InitModel();
+          Schedule(Output,       1);
+          result = Output->Load(element);
+          Outputs.push_back(Output);
+      }
+      else {
+        cerr << "Found unexpected subsystem: " << element_name << ", exiting." << endl;
+        result = false;
+        break;
+      }
+      element = document->GetNextElement();
     }
-    else {
-      cerr << "Found unexpected subsystem: " << element_name << ", exiting." << endl;
-      result = false;
-      break;
-    }
-    element = document->GetNextElement();
+  } else {
+    cerr << fgred
+         << "  JSBSim failed to load aircraft model."
+         << fgdef << endl;
+    return false;
   }
 
   if (result) {
@@ -523,14 +558,14 @@ bool FGFDMExec::LoadModel(string model, bool addModelToPath)
     Debug(3);
   } else {
     cerr << fgred
-         << "  JSBSim failed to load aircraft and/or engine model"
+         << "  JSBSim failed to load properly."
          << fgdef << endl;
     return false;
   }
 
   struct PropertyCatalogStructure masterPCS;
   masterPCS.base_string = "";
-  masterPCS.node = (FGPropertyManager*)master;
+  masterPCS.node = (FGPropertyManager*)Root;
 
   BuildPropertyCatalog(&masterPCS);
 
@@ -689,6 +724,7 @@ bool FGFDMExec::ReadSlave(Element* el)
 
   SlaveFDMList.back()->exec->SetAircraftPath( AircraftPath );
   SlaveFDMList.back()->exec->SetEnginePath( EnginePath );
+  SlaveFDMList.back()->exec->SetSystemsPath( SystemsPath );
   SlaveFDMList.back()->exec->LoadModel(AircraftName);
   debug_lvl = saved_debug_lvl;   // turn debug output back on for master vehicle
 
@@ -754,19 +790,15 @@ void FGFDMExec::EnableOutput(void)
 
 bool FGFDMExec::SetOutputDirectives(string fname)
 {
-  bool result=true; // for now always return true
+  bool result;
+
+  FGOutput* Output = new FGOutput(this);
+  Output->SetDirectivesFile(fname);
+  Output->InitModel();
+  Schedule(Output,       1);
+  result = Output->Load(0);
+  Outputs.push_back(Output);
 
-  if (Outputs.size() == 0) {
-    FGOutput* Output = new FGOutput(this);
-    Output->InitModel();
-    Schedule(Output,       1);
-    Output->SetDirectivesFile(fname);
-    Output->Load(0);
-    Outputs.push_back(Output);
-  } else { // Outputs > 1
-    cerr << "First output file being overridden" << endl;
-    Outputs[0]->SetDirectivesFile(fname);
-  }
   return result;
 }
 
@@ -789,6 +821,38 @@ void FGFDMExec::DoTrim(int mode)
   State->Setsim_time(saved_time);
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+/*
+void FGFDMExec::DoTrimAnalysis(int mode)
+{
+  double saved_time;
+  if (Constructing) return;
+
+  if (mode < 0 || mode > JSBSim::taNone) {
+    cerr << endl << "Illegal trimming mode!" << endl << endl;
+    return;
+  }
+  saved_time = State->Getsim_time();
+
+  FGTrimAnalysis trimAnalysis(this, (JSBSim::TrimAnalysisMode)mode);
+
+  if ( !trimAnalysis.Load(IC->GetInitFile(), false) ) {
+    cerr << "A problem occurred with trim configuration file " << trimAnalysis.Load(IC->GetInitFile()) << endl;
+    exit(-1);
+  }
+
+  bool result = trimAnalysis.DoTrim();
+
+  if ( !result ) cerr << endl << "Trim Failed" << endl << endl;
+
+  trimAnalysis.Report();
+  State->Setsim_time(saved_time);
+
+  EnableOutput();
+  cout << "\nOutput: " << GetOutputFileName() << endl;
+
+}
+*/
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 void FGFDMExec::UseAtmosphereMSIS(void)
index b286fab9c18b0656962d6365003c6b6a2c2527e1..6a92a2e817a128338101949fbd7126f9a2d4afd6 100644 (file)
@@ -53,6 +53,7 @@ INCLUDES
 #include <models/FGPropagate.h>
 
 #include <vector>
+#include <string>
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
@@ -214,6 +215,8 @@ public:
       modeled aircraft such as C172/, x15/, etc.
       @param EnginePath path to the directory under which engine config
       files are kept, for instance "engine"
+      @param SystemsPath path to the directory under which systems config
+      files are kept, for instance "systems"
       @param model the name of the aircraft model itself. This file will
       be looked for in the directory specified in the AircraftPath variable,
       and in turn under the directory with the same name as the model. For
@@ -221,8 +224,8 @@ public:
       @param addModelToPath set to true to add the model name to the
       AircraftPath, defaults to true
       @return true if successful */
-  bool LoadModel(string AircraftPath, string EnginePath, string model,
-                 bool addModelToPath = true);
+  bool LoadModel(string AircraftPath, string EnginePath, string SystemsPath,
+                 string model, bool addModelToPath = true);
 
   /** Loads an aircraft model.  The paths to the aircraft and engine
       config file directories must be set prior to calling this.  See
@@ -251,7 +254,12 @@ public:
       "aircraft". Under aircraft, then, would be directories for various
       modeled aircraft such as C172/, x15/, etc.  */
   bool SetAircraftPath(string path) { AircraftPath = path; return true; }
-
+  
+  /** Sets the path to the systems config file directories.
+      @param path path to the directory under which systems config
+      files are kept, for instance "systems"  */
+  bool SetSystemsPath(string path)   { SystemsPath = path; return true; }
+  
   /// @name Top-level executive State and Model retrieval mechanism
   //@{
   /// Returns the FGAtmosphere pointer.
@@ -268,6 +276,10 @@ public:
   inline FGInertial* GetInertial(void)        {return Inertial;}
   /// Returns the FGGroundReactions pointer.
   inline FGGroundReactions* GetGroundReactions(void) {return GroundReactions;}
+  /// Returns the FGExternalReactions pointer.
+  inline FGExternalReactions* GetExternalReactions(void) {return ExternalReactions;}
+  /// Returns the FGBuoyantForces pointer.
+  inline FGBuoyantForces* GetBuoyantForces(void) {return BuoyantForces;}
   /// Returns the FGAircraft pointer.
   inline FGAircraft* GetAircraft(void)        {return Aircraft;}
   /// Returns the FGPropagate pointer.
@@ -280,16 +292,20 @@ public:
   inline FGGroundCallback* GetGroundCallback(void) {return GroundCallback;}
   /// Returns the FGState pointer.
   inline FGState* GetState(void)              {return State;}
+  /// Retrieves the script object
+  inline FGScript* GetScript(void) {return Script;}
   // Returns a pointer to the FGInitialCondition object
   inline FGInitialCondition* GetIC(void)      {return IC;}
   // Returns a pointer to the FGTrim object
-  inline FGTrim* GetTrim(void);
+  FGTrim* GetTrim(void);
   //@}
 
   /// Retrieves the engine path.
   inline string GetEnginePath(void)          {return EnginePath;}
   /// Retrieves the aircraft path.
   inline string GetAircraftPath(void)        {return AircraftPath;}
+  /// Retrieves the systems path.
+  inline string GetSystemsPath(void)         {return SystemsPath;}
   /// Retrieves the full aircraft path name.
   inline string GetFullAircraftPath(void)    {return FullAircraftPath;}
 
@@ -313,7 +329,7 @@ public:
 
   /// 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)
@@ -365,6 +381,7 @@ public:
   * - tTurn
   * - tNone  */
   void DoTrim(int mode);
+//  void DoTrimAnalysis(int mode);
 
   /// Disables data logging to all outputs.
   void DisableOutput(void);
@@ -376,6 +393,8 @@ 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);
   /// Sets the debug level.
   void SetDebugLevel(int level) {debug_lvl = level;}
 
@@ -409,6 +428,11 @@ public:
   /// Use the Mars atmosphere model. (Not operative yet.)
   void UseAtmosphereMars(void);
 
+  void SetTrimStatus(bool status){ trim_status = status; }
+  bool GetTrimStatus(void) const { return trim_status; }
+  void SetTrimMode(int mode){ ta_mode = mode; }
+  int GetTrimMode(void) const { return ta_mode; }
+
 private:
   static unsigned int FDMctr;
   int Error;
@@ -423,9 +447,14 @@ private:
   string AircraftPath;
   string FullAircraftPath;
   string EnginePath;
+  string SystemsPath;
   string CFGVersion;
   string Release;
 
+  bool trim_status;
+  int ta_mode;
+
+
   struct slaveData {
     FGFDMExec* exec;
     string info;
@@ -457,6 +486,8 @@ private:
   FGAerodynamics*     Aerodynamics;
   FGInertial*         Inertial;
   FGGroundReactions*  GroundReactions;
+  FGExternalReactions* ExternalReactions;
+  FGBuoyantForces*    BuoyantForces;
   FGAircraft*         Aircraft;
   FGPropagate*        Propagate;
   FGAuxiliary*        Auxiliary;
index 259220dbb343b1016c06b187be7d6646ef3bb53a..b5e854d8f47c48daa55b1f4e12ad475aa4c26547 100644 (file)
@@ -81,6 +81,9 @@ const double FGJSBBase::fpstokts = 0.592484;
 const double FGJSBBase::ktstofps = 1.68781;
 const double FGJSBBase::inchtoft = 0.08333333;
 const double FGJSBBase::in3tom3 = 1.638706E-5;
+const double FGJSBBase::m3toft3 = 1.0/(fttom*fttom*fttom);
+const double FGJSBBase::inhgtopa = 3386.38;
+const double FGJSBBase::fttom = 0.3048;
 double FGJSBBase::Reng = 1716.0;
 const double FGJSBBase::SHRatio = 1.40;
 
@@ -92,9 +95,11 @@ const double FGJSBBase::SHRatio = 1.40;
 // Taken from units gnu commandline tool
 const double FGJSBBase::slugtolb = 32.174049;
 const double FGJSBBase::lbtoslug = 1.0/slugtolb;
+const double FGJSBBase::kgtolb = 2.20462;
+const double FGJSBBase::kgtoslug = 0.06852168;
 
 const string FGJSBBase::needed_cfg_version = "2.0";
-const string FGJSBBase::JSBSim_version = "Pre-1.0 "__DATE__" "__TIME__;
+const string FGJSBBase::JSBSim_version = "1.0 "__DATE__" "__TIME__;
 
 std::queue <FGJSBBase::Message> FGJSBBase::Messages;
 FGJSBBase::Message FGJSBBase::localMsg;
index 2dd3637389cc29d78ee4e132a31ea1009e2b6e15..8ec8e828bee9eb744f1b9892c47e41d1d7588ae3 100644 (file)
@@ -39,54 +39,19 @@ INCLUDES
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 #include <float.h>
-
-#ifdef FGFS
-#  include <simgear/compiler.h>
-#  include <math.h>
-#  include <queue>
-#  include STL_STRING
-
-SG_USING_STD(string);
-
-#  ifndef M_PI
-#    include <simgear/constants.h>
-#    define M_PI SG_PI
-#  endif
-
-#else  // JSBSim section
-
-#  include <queue>
-#  include <string>
-#  if defined(sgi) && !defined(__GNUC__)
-#    include <math.h>
-#  else
-#    include <cmath>
-#  endif
-
-using std::string;
-
-#  if defined(_MSC_VER) && _MSC_VER <= 1200
-#    ifndef max
-#      define max(a,b)            (((a) > (b)) ? (a) : (b))
-#    endif
-
-#    ifndef min
-#      define min(a,b)            (((a) < (b)) ? (a) : (b))
-#    endif
-#  else
+#include <queue>
+#include <string>
+#include <cmath>
 
 using std::fabs;
+using std::string;
 
-#  endif
-
-#  ifndef M_PI
-#    define M_PI 3.14159265358979323846
-#  endif
-
+#ifndef M_PI
+#  define M_PI 3.14159265358979323846
 #endif
 
 #if !defined(WIN32) || defined(__GNUC__) || (defined(_MSC_VER) && (_MSC_VER >= 1300))
-using std::max;
+  using std::max;
 #endif
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -212,6 +177,13 @@ void PutMessage(const string& text, double dVal);
     return 1.8*kelvin - 459.4;
   }
 
+  /** Converts from degrees Celsius to degrees Rankine.
+  *   @param celsius The temperature in degrees Celsius.
+  *   @return The temperature in Rankine. */
+  static double CelsiusToRankine (double celsius) {
+    return celsius * 1.8 + 491.67;
+  }
+
   /** Converts from degrees Rankine to degrees Celsius.
   *   @param rankine The temperature in degrees Rankine.
   *   @return The temperature in Celsius. */
@@ -219,6 +191,13 @@ void PutMessage(const string& text, double dVal);
     return (rankine - 491.67)/1.8;
   }
 
+  /** Converts from degrees Kelvin to degrees Rankine.
+  *   @param kelvin The temperature in degrees Kelvin.
+  *   @return The temperature in Rankine. */
+  static double KelvinToRankine (double kelvin) {
+    return kelvin * 1.8;
+  }
+
   /** Converts from degrees Rankine to degrees Kelvin.
   *   @param rankine The temperature in degrees Rankine.
   *   @return The temperature in Kelvin. */
@@ -240,6 +219,20 @@ void PutMessage(const string& text, double dVal);
     return celsius * 1.8 + 32.0;
   }
 
+  /** Converts from degrees Celsius to degrees Kelvin
+  *   @param celsius The temperature in degrees Celsius.
+  *   @return The temperature in Kelvin. */
+  static double CelsiusToKelvin (double celsius) {
+    return celsius + 273.15;
+  }
+
+  /** Converts from degrees Kelvin to degrees Celsius
+  *   @param celsius The temperature in degrees Kelvin.
+  *   @return The temperature in Celsius. */
+  static double KelvinToCelsius (double kelvin) {
+    return kelvin - 273.15;
+  }
+
   /** Finite precision comparison.
       @param a first value to compare
       @param b second value to compare
@@ -273,6 +266,12 @@ void PutMessage(const string& text, double dVal);
   static bool EqualToRoundoff(double a, float b) {
     return EqualToRoundoff((float)a, b);
   }
+  
+  /** Constrain a value between a minimum and a maximum value.
+  */
+  static double Constrain(double min, double value, double max) {
+    return value<min?(min):(value>max?(max):(value));
+  }
 
 protected:
   static Message localMsg;
@@ -292,10 +291,15 @@ protected:
   static const double ktstofps;
   static const double inchtoft;
   static const double in3tom3;
+  static const double m3toft3;
+  static const double inhgtopa;
+  static const double fttom;
   static double Reng;         // Specific Gas Constant,ft^2/(sec^2*R)
   static const double SHRatio;
   static const double lbtoslug;
   static const double slugtolb;
+  static const double kgtolb;
+  static const double kgtoslug;
   static const string needed_cfg_version;
   static const string JSBSim_version;
 
index 29c174132afc8e231d5e036ca88b3e5bebd8ec42..53d40ec2ced15c03014ec2f4483bda2e018c5485 100644 (file)
@@ -88,7 +88,6 @@ FGState::FGState(FGFDMExec* fdex)
 
 FGState::~FGState()
 {
-  unbind();
   Debug(1);
 }
 
@@ -131,73 +130,11 @@ void FGState::Initialize(FGInitialCondition *FGIC)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-FGMatrix33& FGState::GetTs2b(void)
-{
-  double ca, cb, sa, sb;
-
-  double alpha = Auxiliary->Getalpha();
-  double beta  = Auxiliary->Getbeta();
-
-  ca = cos(alpha);
-  sa = sin(alpha);
-  cb = cos(beta);
-  sb = sin(beta);
-
-  mTs2b(1,1) = ca*cb;
-  mTs2b(1,2) = -ca*sb;
-  mTs2b(1,3) = -sa;
-  mTs2b(2,1) = sb;
-  mTs2b(2,2) = cb;
-  mTs2b(2,3) = 0.0;
-  mTs2b(3,1) = sa*cb;
-  mTs2b(3,2) = -sa*sb;
-  mTs2b(3,3) = ca;
-
-  return mTs2b;
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-FGMatrix33& FGState::GetTb2s(void)
-{
-  double alpha,beta;
-  double ca, cb, sa, sb;
-
-  alpha = Auxiliary->Getalpha();
-  beta  = Auxiliary->Getbeta();
-
-  ca = cos(alpha);
-  sa = sin(alpha);
-  cb = cos(beta);
-  sb = sin(beta);
-
-  mTb2s(1,1) = ca*cb;
-  mTb2s(1,2) = sb;
-  mTb2s(1,3) = sa*cb;
-  mTb2s(2,1) = -ca*sb;
-  mTb2s(2,2) = cb;
-  mTb2s(2,3) = -sa*sb;
-  mTb2s(3,1) = -sa;
-  mTb2s(3,2) = 0.0;
-  mTb2s(3,3) = ca;
-
-  return mTb2s;
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
 void FGState::bind(void)
 {
   PropertyManager->Tie("sim-time-sec", this, &FGState::Getsim_time);
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGState::unbind(void)
-{
-  PropertyManager->Untie("sim-time-sec");
-}
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index aad679f378a9d8a2b6bf16cd5bc3bbed58d351ac..079377c15ef8c76bd6d40707ba777f6e42abba35 100644 (file)
@@ -60,7 +60,6 @@ INCLUDES
 #include <map>
 #include "FGJSBBase.h"
 #include <initialization/FGInitialCondition.h>
-#include <math/FGMatrix33.h>
 #include <math/FGColumnVector3.h>
 #include <math/FGQuaternion.h>
 #include "FGFDMExec.h"
@@ -149,27 +148,15 @@ public:
     return sim_time;
   }
 
-  /** Calculates and returns the stability-to-body axis transformation matrix.
-      @return a reference to the stability-to-body transformation matrix.
-      */
-  FGMatrix33& GetTs2b(void);
-
-  /** Calculates and returns the body-to-stability axis transformation matrix.
-      @return a reference to the stability-to-body transformation matrix.
-      */
-  FGMatrix33& GetTb2s(void);
-
   /** Prints a summary of simulator state (speed, altitude,
       configuration, etc.)  */
-  void ReportState(void);
+//  void ReportState(void);
 
 private:
   double sim_time, dt;
   double saved_dt;
 
   FGFDMExec* FDMExec;
-  FGMatrix33 mTs2b;
-  FGMatrix33 mTb2s;
 
   FGAircraft* Aircraft;
   FGPropagate* Propagate;
@@ -182,7 +169,6 @@ private:
   FGPropertyManager* PropertyManager;
 
   void bind();
-  void unbind();
 
   void Debug(int from);
 };
index 2b59f324091ae2ddbcaa9c4cb7691aa655b0fee1..aa287f0d4656d3cdb2f9b69c396e7ab00d46b7f1 100644 (file)
@@ -27,7 +27,7 @@
 
 #include <simgear/compiler.h>
 
-#include <stdio.h>     //      size_t
+#include <stdio.h>    //    size_t
 #ifdef SG_MATH_EXCEPTION_CLASH
 #  include <math.h>
 #endif
@@ -58,6 +58,7 @@
 #include <FDM/JSBSim/models/FGFCS.h>
 #include <FDM/JSBSim/models/FGPropagate.h>
 #include <FDM/JSBSim/models/FGAuxiliary.h>
+#include <FDM/JSBSim/models/FGInertial.h>
 #include <FDM/JSBSim/models/FGAtmosphere.h>
 #include <FDM/JSBSim/models/FGMassBalance.h>
 #include <FDM/JSBSim/models/FGAerodynamics.h>
@@ -119,7 +120,7 @@ private:
 /******************************************************************************/
 
 FGJSBsim::FGJSBsim( double dt )
-  : FGInterface(dt)
+  : FGInterface(dt), got_wire(false)
 {
     bool result;
                                 // Set up the debugging level
@@ -160,6 +161,7 @@ FGJSBsim::FGJSBsim( double dt )
     Aircraft        = fdmex->GetAircraft();
     Propagate        = fdmex->GetPropagate();
     Auxiliary       = fdmex->GetAuxiliary();
+    Inertial        = fdmex->GetInertial();
     Aerodynamics    = fdmex->GetAerodynamics();
     GroundReactions = fdmex->GetGroundReactions();
 
@@ -170,10 +172,15 @@ FGJSBsim::FGJSBsim( double dt )
 
     SGPath engine_path( fgGetString("/sim/aircraft-dir") );
     engine_path.append( "Engine" );
+
+    SGPath systems_path( fgGetString("/sim/aircraft-dir") );
+    systems_path.append( "Systems" );
+
     State->Setdt( dt );
 
     result = fdmex->LoadModel( aircraft_path.str(),
                                engine_path.str(),
+                               systems_path.str(),
                                fgGetString("/sim/aero"), false );
 
     if (result) {
@@ -211,6 +218,8 @@ FGJSBsim::FGJSBsim( double dt )
         node->setDoubleValue("level-lb", Propulsion->GetTank(i)->GetContents());
         node->setDoubleValue("level-gal_us", Propulsion->GetTank(i)->GetContents() / 6.6);
       }
+      node->setDoubleValue("capacity-gal_us",
+                           Propulsion->GetTank(i)->GetCapacity() / 6.6);
     }
     Propulsion->SetFuelFreeze((fgGetNode("/sim/freeze/fuel",true))->getBoolValue());
 
@@ -269,6 +278,11 @@ FGJSBsim::FGJSBsim( double dt )
       Propulsion->GetEngine(i)->GetThruster()->SetRPM(node->getDoubleValue("rpm") /
                      Propulsion->GetEngine(i)->GetThruster()->GetGearRatio());
     }
+
+    hook_root_struct = FGColumnVector3(
+        fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-offset-x-in", 196),
+        fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-offset-y-in", 0),
+        fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-offset-z-in", -16));
 }
 
 /******************************************************************************/
@@ -297,20 +311,16 @@ void FGJSBsim::init()
                   9.0/5.0*(temperature->getDoubleValue()+273.15) );
       Atmosphere->SetExPressure(pressure->getDoubleValue()*70.726566);
       Atmosphere->SetExDensity(density->getDoubleValue());
-
-      tmp = turbulence_gain->getDoubleValue();
-      Atmosphere->SetTurbGain(tmp * tmp * 100.0);
-
-      tmp = turbulence_rate->getDoubleValue();
-      Atmosphere->SetTurbRate(tmp);
+      Atmosphere->SetTurbGain(turbulence_gain->getDoubleValue());
+      Atmosphere->SetTurbRate(turbulence_rate->getDoubleValue());
 
     } else {
       Atmosphere->UseInternal();
     }
 
-    fgic->SetVnorthFpsIC( wind_from_north->getDoubleValue() );
-    fgic->SetVeastFpsIC( wind_from_east->getDoubleValue() );
-    fgic->SetVdownFpsIC( wind_from_down->getDoubleValue() );
+    fgic->SetVNorthFpsIC( wind_from_north->getDoubleValue() );
+    fgic->SetVEastFpsIC( wind_from_east->getDoubleValue() );
+    fgic->SetVDownFpsIC( wind_from_down->getDoubleValue() );
 
     //Atmosphere->SetExTemperature(get_Static_temperature());
     //Atmosphere->SetExPressure(get_Static_pressure());
@@ -327,6 +337,8 @@ void FGJSBsim::init()
           }
     }
 
+    FCS->SetDfPos( ofNorm, globals->get_controls()->get_flaps() );
+
     common_init();
 
     copy_to_JSBsim();
@@ -463,6 +475,7 @@ void FGJSBsim::update( double dt )
 
     for ( i=0; i < multiloop; i++ ) {
       fdmex->Run();
+      update_external_forces(State->Getsim_time() + i * State->Getdt());      
     }
 
     FGJSBBase::Message* msg;
@@ -509,8 +522,6 @@ bool FGJSBsim::copy_to_JSBsim()
     FCS->SetPitchTrimCmd( globals->get_controls()->get_elevator_trim() );
     FCS->SetDrCmd( -globals->get_controls()->get_rudder() );
     FCS->SetYawTrimCmd( -globals->get_controls()->get_rudder_trim() );
-    // FIXME: make that get_steering work
-//     FCS->SetDsCmd( globals->get_controls()->get_steering()/80.0 );
     FCS->SetDsCmd( globals->get_controls()->get_rudder() );
     FCS->SetDfCmd( globals->get_controls()->get_flaps() );
     FCS->SetDsbCmd( globals->get_controls()->get_speedbrake() );
@@ -545,7 +556,7 @@ bool FGJSBsim::copy_to_JSBsim()
         FGTurbine* eng = (FGTurbine*)Propulsion->GetEngine(i);
         eng->SetAugmentation( globals->get_controls()->get_augmentation(i) );
         eng->SetReverse( globals->get_controls()->get_reverser(i) );
-        eng->SetInjection( globals->get_controls()->get_water_injection(i) );
+        //eng->SetInjection( globals->get_controls()->get_water_injection(i) );
         eng->SetCutoff( globals->get_controls()->get_cutoff(i) );
         eng->SetIgnition( globals->get_controls()->get_ignition(i) );
         break;
@@ -562,8 +573,8 @@ bool FGJSBsim::copy_to_JSBsim()
         eng->SetCutoff( globals->get_controls()->get_cutoff(i) );
         eng->SetIgnition( globals->get_controls()->get_ignition(i) );
 
-               eng->SetGeneratorPower( globals->get_controls()->get_generator_breaker(i) );
-               eng->SetCondition( globals->get_controls()->get_condition(i) );
+        eng->SetGeneratorPower( globals->get_controls()->get_generator_breaker(i) );
+        eng->SetCondition( globals->get_controls()->get_condition(i) );
         break;
         } // end FGTurboProp code block
       }
@@ -585,10 +596,10 @@ bool FGJSBsim::copy_to_JSBsim()
     Atmosphere->SetExDensity(density->getDoubleValue());
 
     tmp = turbulence_gain->getDoubleValue();
-    Atmosphere->SetTurbGain(tmp * tmp * 100.0);
+    //Atmosphere->SetTurbGain(tmp * tmp * 100.0);
 
     tmp = turbulence_rate->getDoubleValue();
-    Atmosphere->SetTurbRate(tmp);
+    //Atmosphere->SetTurbRate(tmp);
 
     Atmosphere->SetWindNED( wind_from_north->getDoubleValue(),
                             wind_from_east->getDoubleValue(),
@@ -604,8 +615,7 @@ bool FGJSBsim::copy_to_JSBsim()
       tank->SetContents(node->getDoubleValue("level-gal_us") * 6.6);
 //       tank->SetContents(node->getDoubleValue("level-lb"));
     }
-    SGPropertyNode* node = fgGetNode("/systems/refuel", true);
-    Propulsion->SetRefuel(node->getDoubleValue("contact"));
+
     Propulsion->SetFuelFreeze((fgGetNode("/sim/freeze/fuel",true))->getBoolValue());
     fdmex->SetSlave(slaved->getBoolValue());
 
@@ -704,7 +714,7 @@ bool FGJSBsim::copy_from_JSBsim()
 
     _set_Gamma_vert_rad( Auxiliary->GetGamma() );
 
-    _set_Earth_position_angle( Auxiliary->GetEarthPositionAngle() );
+    _set_Earth_position_angle( Inertial->GetEarthPositionAngle() );
 
     _set_Climb_Rate( Propagate->Gethdot() );
 
@@ -985,9 +995,9 @@ void FGJSBsim::set_Velocities_Local( double north, double east, double down )
     FGInterface::set_Velocities_Local(north, east, down);
 
     update_ic();
-    fgic->SetVnorthFpsIC(north);
-    fgic->SetVeastFpsIC(east);
-    fgic->SetVdownFpsIC(down);
+    fgic->SetVNorthFpsIC(north);
+    fgic->SetVEastFpsIC(east);
+    fgic->SetVDownFpsIC(down);
     needTrim=true;
 }
 
@@ -1063,7 +1073,7 @@ void FGJSBsim::init_gear(void )
       node->setDoubleValue("zoffset-in", gear->GetBodyLocation()(3));
       node->setBoolValue("wow", gear->GetWOW());
       node->setBoolValue("has-brake", gear->GetBrakeGroup() > 0);
-      node->setDoubleValue("position-norm", FCS->GetGearPos());
+      node->setDoubleValue("position-norm", gear->GetGearUnitPos());
       node->setDoubleValue("tire-pressure-norm", gear->GetTirePressure());
       node->setDoubleValue("compression-norm", gear->GetCompLen());
       if ( gear->GetSteerable() )
@@ -1079,7 +1089,7 @@ void FGJSBsim::update_gear(void)
       FGLGear *gear = gr->GetGearUnit(i);
       SGPropertyNode * node = fgGetNode("gear/gear", i, true);
       node->getChild("wow", 0, true)->setBoolValue( gear->GetWOW());
-      node->getChild("position-norm", 0, true)->setDoubleValue(FCS->GetGearPos());
+      node->getChild("position-norm", 0, true)->setDoubleValue(gear->GetGearUnitPos());
       gear->SetTirePressure(node->getDoubleValue("tire-pressure-norm"));
       node->setDoubleValue("compression-norm", gear->GetCompLen());
       if ( gear->GetSteerable() )
@@ -1093,7 +1103,6 @@ void FGJSBsim::do_trim(void)
 
   if ( fgGetBool("/sim/presets/onground") )
   {
-    fgic->SetVcalibratedKtsIC(0.0);
     fgtrim = new FGTrim(fdmex,tGround);
   } else {
     fgtrim = new FGTrim(fdmex,tLongitudinal);
@@ -1105,10 +1114,8 @@ void FGJSBsim::do_trim(void)
   } else {
     trimmed->setBoolValue(true);
   }
-#if 0
-  if (FGJSBBase::debug_lvl > 0)
-      State->ReportState();    /* FIXME: Function not implemented */
-#endif
+//  if (FGJSBBase::debug_lvl > 0)
+//      State->ReportState();
 
   delete fgtrim;
 
@@ -1142,3 +1149,190 @@ void FGJSBsim::update_ic(void)
    }
 }
 
+inline static double dot3(const FGColumnVector3& a, const FGColumnVector3& b)
+{
+    return a(1) * b(1) + a(2) * b(2) + a(3) * b(3);
+}
+
+inline static double sqr(double x)
+{
+    return x * x;
+}
+
+static double angle_diff(double a, double b)
+{
+    double diff = fabs(a - b);
+    if (diff > 180) diff = 360 - diff;
+    
+    return diff;
+}
+
+static void check_hook_solution(const FGColumnVector3& ground_normal_body, double E, double hook_length, double sin_fi_guess, double cos_fi_guess, double* sin_fis, double* cos_fis, double* fis, int* points)
+{
+    FGColumnVector3 tip(-hook_length * cos_fi_guess, 0, hook_length * sin_fi_guess);
+    double dist = dot3(tip, ground_normal_body);
+    if (fabs(dist + E) < 0.0001) {
+       sin_fis[*points] = sin_fi_guess;
+       cos_fis[*points] = cos_fi_guess;
+       fis[*points] = atan2(sin_fi_guess, cos_fi_guess) * SG_RADIANS_TO_DEGREES;
+       (*points)++;
+    } 
+}
+
+
+static void check_hook_solution(const FGColumnVector3& ground_normal_body, double E, double hook_length, double sin_fi_guess, double* sin_fis, double* cos_fis, double* fis, int* points)
+{
+    if (sin_fi_guess >= -1 && sin_fi_guess <= 1) {
+       double cos_fi_guess = sqrt(1 - sqr(sin_fi_guess));
+       check_hook_solution(ground_normal_body, E, hook_length, sin_fi_guess, cos_fi_guess, sin_fis, cos_fis, fis, points);
+       if (fabs(cos_fi_guess) > SG_EPSILON) {
+           check_hook_solution(ground_normal_body, E, hook_length, sin_fi_guess, -cos_fi_guess, sin_fis, cos_fis, fis, points);
+       }
+    }
+}
+
+void FGJSBsim::update_external_forces(double t_off)
+{
+    const FGMatrix33& Tb2l = Propagate->GetTb2l();
+    const FGMatrix33& Tl2b = Propagate->GetTl2b();
+    const FGLocation& Location = Propagate->GetLocation();
+    const FGMatrix33& Tec2l = Location.GetTec2l();
+        
+    double hook_area[4][3];
+    
+    FGColumnVector3 hook_root_body = MassBalance->StructuralToBody(hook_root_struct);
+    FGColumnVector3 hook_root = Location.LocalToLocation(Tb2l *   hook_root_body);
+    hook_area[1][0] = hook_root(1);
+    hook_area[1][1] = hook_root(2);
+    hook_area[1][2] = hook_root(3);
+    
+    hook_length = fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-length-ft", 6.75);
+    double fi_min = fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-pos-min-deg", -18);
+    double fi_max = fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-pos-max-deg", 30);
+    double fi = fgGetDouble("/fdm/jsbsim/systems/hook/tailhook-pos-norm") * (fi_max - fi_min) + fi_min;
+    double cos_fi = cos(fi * SG_DEGREES_TO_RADIANS);
+    double sin_fi = sin(fi * SG_DEGREES_TO_RADIANS);
+
+    FGColumnVector3 hook_tip_body = hook_root_body;
+    hook_tip_body(1) -= hook_length * cos_fi;
+    hook_tip_body(3) += hook_length * sin_fi;    
+    bool hook_tip_valid = true;
+    
+    double contact[3];
+    double ground_normal[3];
+    double ground_vel[3];
+    int ground_type;
+    const SGMaterial* ground_material;
+    double root_agl_ft;
+
+    if (!got_wire) {
+        bool got = get_agl_ft(t_off, hook_area[1], 0, contact, ground_normal, ground_vel, &ground_type, &ground_material, &root_agl_ft);
+        if (got && root_agl_ft > 0 && root_agl_ft < hook_length) {
+            FGColumnVector3 ground_normal_body = Tl2b * (Tec2l * FGColumnVector3(ground_normal[0], ground_normal[1], ground_normal[2]));
+            FGColumnVector3 contact_body = Tl2b * Location.LocationToLocal(FGColumnVector3(contact[0], contact[1], contact[2]));
+            double D = -dot3(contact_body, ground_normal_body);
+
+           // check hook tip agl against same ground plane
+           double hook_tip_agl_ft = dot3(hook_tip_body, ground_normal_body) + D;
+           if (hook_tip_agl_ft < 0) {
+
+               // hook tip: hx - l cos, hy, hz + l sin
+               // on ground:  - n0 l cos + n2 l sin + E = 0
+
+               double E = D + dot3(hook_root_body, ground_normal_body);
+
+               // substitue x = sin fi, cos fi = sqrt(1 - x * x)
+               // and rearrange to get a quadratic with coeffs:
+               double a = sqr(hook_length) * (sqr(ground_normal_body(1)) + sqr(ground_normal_body(3)));
+               double b = 2 * E * ground_normal_body(3) * hook_length;
+               double c = sqr(E) - sqr(ground_normal_body(1) * hook_length);   
+
+               double disc = sqr(b) - 4 * a * c;
+               if (disc >= 0) {
+                   double delta = sqrt(disc) / (2 * a);
+               
+                   // allow 4 solutions for safety, should never happen
+                   double sin_fis[4];
+                   double cos_fis[4];
+                   double fis[4];
+                   int points = 0;
+               
+                   double sin_fi_guess = -b / (2 * a) - delta;
+                   check_hook_solution(ground_normal_body, E, hook_length, sin_fi_guess, sin_fis, cos_fis, fis, &points);
+                   check_hook_solution(ground_normal_body, E, hook_length, sin_fi_guess + 2 * delta, sin_fis, cos_fis, fis, &points);
+               
+                   if (points == 2) {
+                       double diff1 = angle_diff(fi, fis[0]);
+                       double diff2 = angle_diff(fi, fis[1]);
+                       int point = diff1 < diff2 ? 0 : 1;
+                       fi = fis[point];
+                       sin_fi = sin_fis[point];
+                       cos_fi = cos_fis[point];
+                       hook_tip_body(1) = hook_root_body(1) - hook_length * cos_fi;
+                       hook_tip_body(3) = hook_root_body(3) + hook_length * sin_fi;
+                   }
+               }
+           }
+       }
+    } else {
+        FGColumnVector3 hook_root_vel = Propagate->GetVel() + (Tb2l * (Propagate->GetPQR() *  hook_root_body));
+        double wire_ends_ec[2][3];
+        double wire_vel_ec[2][3];
+        get_wire_ends_ft(t_off, wire_ends_ec, wire_vel_ec);
+        FGColumnVector3 wire_vel_1 = Tec2l * FGColumnVector3(wire_vel_ec[0][0], wire_vel_ec[0][1], wire_vel_ec[0][2]);
+        FGColumnVector3 wire_vel_2 = Tec2l * FGColumnVector3(wire_vel_ec[1][0], wire_vel_ec[1][1], wire_vel_ec[1][2]);
+        FGColumnVector3 rel_vel = hook_root_vel - (wire_vel_1 + wire_vel_2) / 2;
+        if (rel_vel.Magnitude() < 3) {
+            got_wire = false;
+            release_wire();
+            fgSetDouble("/fdm/jsbsim/external_reactions/hook/magnitude", 0.0);
+        } else {
+            FGColumnVector3 wire_end1_body = Tl2b * Location.LocationToLocal(FGColumnVector3(wire_ends_ec[0][0], wire_ends_ec[0][1], wire_ends_ec[0][2])) - hook_root_body;
+            FGColumnVector3 wire_end2_body = Tl2b * Location.LocationToLocal(FGColumnVector3(wire_ends_ec[1][0], wire_ends_ec[1][1], wire_ends_ec[1][2])) - hook_root_body;
+            FGColumnVector3 force_plane_normal = wire_end1_body * wire_end2_body;
+            force_plane_normal.Normalize();
+            cos_fi = dot3(force_plane_normal, FGColumnVector3(0, 0, 1));
+            if (cos_fi < 0) cos_fi = -cos_fi;
+            sin_fi = sqrt(1 - sqr(cos_fi));
+            fi = atan2(sin_fi, cos_fi) * SG_RADIANS_TO_DEGREES;
+        
+            fgSetDouble("/fdm/jsbsim/external_reactions/hook/x", -cos_fi);
+            fgSetDouble("/fdm/jsbsim/external_reactions/hook/y", 0);
+            fgSetDouble("/fdm/jsbsim/external_reactions/hook/z", sin_fi);
+            fgSetDouble("/fdm/jsbsim/external_reactions/hook/magnitude", fgGetDouble("/fdm/jsbsim/systems/hook/force"));
+        }
+    }
+
+    FGColumnVector3 hook_tip = Location.LocalToLocation(Tb2l * hook_tip_body);
+
+    hook_area[0][0] = hook_tip(1);
+    hook_area[0][1] = hook_tip(2);
+    hook_area[0][2] = hook_tip(3);
+
+    if (!got_wire) {
+        // The previous positions.
+        hook_area[2][0] = last_hook_root[0];
+        hook_area[2][1] = last_hook_root[1];
+        hook_area[2][2] = last_hook_root[2];
+        hook_area[3][0] = last_hook_tip[0];
+        hook_area[3][1] = last_hook_tip[1];
+        hook_area[3][2] = last_hook_tip[2];
+
+        // Check if we caught a wire.
+        // Returns true if we caught one.
+        if (caught_wire_ft(t_off, hook_area)) {
+                got_wire = true;
+        }
+    }
+    
+    // save actual position as old position ...
+    last_hook_tip[0] = hook_area[0][0];
+    last_hook_tip[1] = hook_area[0][1];
+    last_hook_tip[2] = hook_area[0][2];
+    last_hook_root[0] = hook_area[1][0];
+    last_hook_root[1] = hook_area[1][1];
+    last_hook_root[2] = hook_area[1][2];
+    
+    fgSetDouble("/fdm/jsbsim/systems/hook/tailhook-pos-deg", fi);
+}
+
index cc2cfb03aebdd1cda80a9e0264a15c7ee6ccd0bf..6fa38fdb1111eedaed276f34275392b5c59bbbc4 100644 (file)
@@ -39,6 +39,7 @@ INCLUDES
 
 #undef MAX_ENGINES
 #include <Aircraft/aircraft.hxx>
+#include "math/FGColumnVector3.h"
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
@@ -220,7 +221,8 @@ private:
     JSBSim::FGPropagate*    Propagate;
     JSBSim::FGAuxiliary*    Auxiliary;
     JSBSim::FGAerodynamics* Aerodynamics;
-    JSBSim::FGGroundReactions *GroundReactions;
+    JSBSim::FGGroundReactions* GroundReactions;
+    JSBSim::FGInertial*     Inertial;
 
     int runcount;
     double trim_elev;
@@ -263,9 +265,17 @@ private:
 
     SGPropertyNode_ptr slaved;
 
+    double last_hook_tip[3];
+    double last_hook_root[3];
+    JSBSim::FGColumnVector3 hook_root_struct;
+    double hook_length;
+    bool got_wire;
+
     void init_gear(void);
     void update_gear(void);
 
+    void update_external_forces(double t_off);
+
 };
 
 
index 7c2dc3dfcaf6f0b84592e89aef5df0714ccf160b..5975a048a035c964456d04159d82c1defc32cdc8 100644 (file)
@@ -67,6 +67,8 @@ INCLUDES
 #include <models/FGPropulsion.h>
 #include <input_output/FGXMLParse.h>
 
+#include <math/FGQuaternion.h>
+
 namespace JSBSim {
 
 static const char *IdSrc = "$Id$";
@@ -74,7 +76,72 @@ static const char *IdHdr = ID_INITIALCONDITION;
 
 //******************************************************************************
 
-FGInitialCondition::FGInitialCondition(FGFDMExec *FDMExec)
+FGInitialCondition::FGInitialCondition(FGFDMExec *FDMExec) : fdmex(FDMExec)
+{
+  InitializeIC();
+
+  if(FDMExec != NULL ) {
+    fdmex->GetPropagate()->Seth(altitude);
+    fdmex->GetAtmosphere()->Run();
+    PropertyManager=fdmex->GetPropertyManager();
+    bind();
+  } else {
+    cout << "FGInitialCondition: This class requires a pointer to a valid FGFDMExec object" << endl;
+  }
+
+  Debug(0);
+}
+
+//******************************************************************************
+
+FGInitialCondition::~FGInitialCondition()
+{
+  Debug(1);
+}
+
+//******************************************************************************
+
+void FGInitialCondition::ResetIC(double u0, double v0, double w0,
+                                 double p0, double q0, double r0,
+                                 double alpha0, double beta0,
+                                 double phi0, double theta0, double psi0,
+                                 double latRad0, double lonRad0, double altAGLFt0,
+                                 double gamma0)
+{
+  InitializeIC();
+
+  u = u0;  v = v0;  w = w0;
+  p = p0;  q = q0;  r = r0;
+  alpha = alpha0;  beta = beta0;
+  phi = phi0;  theta = theta0;  psi = psi0;
+  gamma = gamma0;
+
+  latitude = latRad0;
+  longitude = lonRad0;
+  SetAltitudeAGLFtIC(altAGLFt0);
+
+  cphi   = cos(phi);   sphi   = sin(phi);   // phi, rad
+  ctheta = cos(theta); stheta = sin(theta); // theta, rad
+  cpsi   = cos(psi);   spsi   = sin(psi);   // psi, rad
+
+  FGQuaternion Quat( phi, theta, psi );
+  Quat.Normalize();
+
+  const FGMatrix33& _Tl2b  = Quat.GetT();     // local to body frame
+  const FGMatrix33& _Tb2l  = Quat.GetTInv();  // body to local
+
+  FGColumnVector3 _vUVW_BODY(u,v,w);
+  FGColumnVector3 _vUVW_NED = _Tb2l * _vUVW_BODY;
+  FGColumnVector3 _vWIND_NED(wnorth,weast,wdown);
+  FGColumnVector3 _vUVWAero = _Tl2b * ( _vUVW_NED + _vWIND_NED );
+
+  uw=_vWIND_NED(1); vw=_vWIND_NED(2); ww=_vWIND_NED(3);
+
+}
+
+//******************************************************************************
+
+void FGInitialCondition::InitializeIC(void)
 {
   vt=vc=ve=vg=0;
   mach=0;
@@ -91,32 +158,41 @@ FGInitialCondition::FGInitialCondition(FGFDMExec *FDMExec)
   wdir=wmag=0;
   lastSpeedSet=setvt;
   lastWindSet=setwned;
-  sea_level_radius = FDMExec->GetInertial()->RefRadius();
-  radius_to_vehicle = FDMExec->GetInertial()->RefRadius();
+  radius_to_vehicle = sea_level_radius = fdmex->GetInertial()->GetRefRadius();
   terrain_altitude = 0;
 
+  targetNlfIC = 1.0;
+
   salpha=sbeta=stheta=sphi=spsi=sgamma=0;
   calpha=cbeta=ctheta=cphi=cpsi=cgamma=1;
-
-  if(FDMExec != NULL ) {
-    fdmex=FDMExec;
-    fdmex->GetPropagate()->Seth(altitude);
-    fdmex->GetAtmosphere()->Run();
-    PropertyManager=fdmex->GetPropertyManager();
-    bind();
-  } else {
-    cout << "FGInitialCondition: This class requires a pointer to a valid FGFDMExec object" << endl;
-  }
-
-  Debug(0);
 }
 
 //******************************************************************************
 
-FGInitialCondition::~FGInitialCondition()
+void FGInitialCondition::WriteStateFile(int num)
 {
-  unbind();
-  Debug(1);
+  string filename = fdmex->GetFullAircraftPath() + "/" + "initfile.xml";
+  ofstream outfile(filename.c_str());
+  FGPropagate* Propagate = fdmex->GetPropagate();
+  
+  if (outfile.is_open()) {
+    outfile << "<?xml version=\"1.0\"?>" << endl;
+    outfile << "<initialize name=\"reset00\">" << endl;
+    outfile << "  <ubody unit=\"FT/SEC\"> " << Propagate->GetUVW(eX) << " </ubody> " << endl;
+    outfile << "  <vbody unit=\"FT/SEC\"> " << Propagate->GetUVW(eY) << " </vbody> " << endl;
+    outfile << "  <wbody unit=\"FT/SEC\"> " << Propagate->GetUVW(eZ) << " </wbody> " << endl;
+    outfile << "  <phi unit=\"DEG\"> " << Propagate->GetEuler(ePhi) << " </phi>" << endl;
+    outfile << "  <theta unit=\"DEG\"> " << Propagate->GetEuler(eTht) << " </theta>" << endl;
+    outfile << "  <psi unit=\"DEG\"> " << Propagate->GetEuler(ePsi) << " </psi>" << endl;
+    outfile << "  <longitude unit=\"DEG\"> " << Propagate->GetLongitudeDeg() << " </longitude>" << endl;
+    outfile << "  <latitude unit=\"DEG\"> " << Propagate->GetLatitudeDeg() << " </latitude>" << endl;
+    outfile << "  <altitude unit=\"FT\"> " << Propagate->Geth() << " </altitude>" << endl;
+    outfile << "</initialize>" << endl;
+  } else {
+    cerr << "Could not open and/or write the state to the initial conditions file." << endl;
+  }
+
+  outfile.close();
 }
 
 //******************************************************************************
@@ -280,10 +356,69 @@ void FGInitialCondition::SetWBodyFpsIC(double tt) {
   lastSpeedSet=setuvw;
 }
 
+
+//******************************************************************************
+
+void FGInitialCondition::SetVNorthFpsIC(double tt) {
+  double ua,va,wa;
+  double vxz;
+  vnorth = tt;
+  calcUVWfromNED();
+  ua = u + uw; va = v + vw; wa = w + ww;
+  vt = sqrt( ua*ua + va*va + wa*wa );
+  alpha = beta = 0;
+  vxz = sqrt( u*u + w*w );
+  if( w != 0 ) alpha = atan2( w, u );
+  if( vxz != 0 ) beta = atan2( v, vxz );
+  mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
+  vc=calcVcas(mach);
+  ve=vt*sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
+  lastSpeedSet=setned;
+}
+
+//******************************************************************************
+
+void FGInitialCondition::SetVEastFpsIC(double tt) {
+  double ua,va,wa;
+  double vxz;
+  veast = tt;
+  calcUVWfromNED();
+  ua = u + uw; va = v + vw; wa = w + ww;
+  vt = sqrt( ua*ua + va*va + wa*wa );
+  alpha = beta = 0;
+  vxz = sqrt( u*u + w*w );
+  if( w != 0 ) alpha = atan2( w, u );
+  if( vxz != 0 ) beta = atan2( v, vxz );
+  mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
+  vc=calcVcas(mach);
+  ve=vt*sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
+  lastSpeedSet=setned;
+}
+
+//******************************************************************************
+
+void FGInitialCondition::SetVDownFpsIC(double tt) {
+  double ua,va,wa;
+  double vxz;
+  vdown = tt;
+  calcUVWfromNED();
+  ua = u + uw; va = v + vw; wa = w + ww;
+  vt = sqrt( ua*ua + va*va + wa*wa );
+  alpha = beta = 0;
+  vxz = sqrt( u*u + w*w );
+  if( w != 0 ) alpha = atan2( w, u );
+  if( vxz != 0 ) beta = atan2( v, vxz );
+  mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
+  vc=calcVcas(mach);
+  ve=vt*sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
+  SetClimbRateFpsIC(-1*vdown);
+  lastSpeedSet=setned;
+}
+
 //******************************************************************************
 
 double FGInitialCondition::GetUBodyFpsIC(void) const {
-    if(lastSpeedSet == setvg )
+    if (lastSpeedSet == setvg || lastSpeedSet == setned)
       return u;
     else
       return vt*calpha*cbeta - uw;
@@ -292,7 +427,7 @@ double FGInitialCondition::GetUBodyFpsIC(void) const {
 //******************************************************************************
 
 double FGInitialCondition::GetVBodyFpsIC(void) const {
-    if( lastSpeedSet == setvg )
+    if (lastSpeedSet == setvg || lastSpeedSet == setned)
       return v;
     else {
       return vt*sbeta - vw;
@@ -302,7 +437,7 @@ double FGInitialCondition::GetVBodyFpsIC(void) const {
 //******************************************************************************
 
 double FGInitialCondition::GetWBodyFpsIC(void) const {
-    if( lastSpeedSet == setvg )
+    if (lastSpeedSet == setvg || lastSpeedSet == setned)
       return w;
     else
       return vt*salpha*cbeta -ww;
@@ -470,34 +605,6 @@ void FGInitialCondition::calcUVWfromNED(void) {
 
 //******************************************************************************
 
-void FGInitialCondition::SetVnorthFpsIC(double tt) {
-  vnorth=tt;
-  calcUVWfromNED();
-  vt=sqrt(u*u + v*v + w*w);
-  lastSpeedSet=setned;
-}
-
-//******************************************************************************
-
-void FGInitialCondition::SetVeastFpsIC(double tt) {
-  veast=tt;
-  calcUVWfromNED();
-  vt=sqrt(u*u + v*v + w*w);
-  lastSpeedSet=setned;
-}
-
-//******************************************************************************
-
-void FGInitialCondition::SetVdownFpsIC(double tt) {
-  vdown=tt;
-  calcUVWfromNED();
-  vt=sqrt(u*u + v*v + w*w);
-  SetClimbRateFpsIC(-1*vdown);
-  lastSpeedSet=setned;
-}
-
-//******************************************************************************
-
 bool FGInitialCondition::getMachFromVcas(double *Mach,double vcas) {
 
   bool result=false;
@@ -731,7 +838,6 @@ double FGInitialCondition::GetWindDirDegIC(void) const {
 
 bool FGInitialCondition::Load(string rstfile, bool useStoredPath)
 {
-  string resetDef;
   int n;
 
   string sep = "/";
@@ -740,40 +846,54 @@ bool FGInitialCondition::Load(string rstfile, bool useStoredPath)
 # endif
 
   if( useStoredPath ) {
-    resetDef = fdmex->GetFullAircraftPath() + sep + rstfile + ".xml";
+    init_file_name = fdmex->GetFullAircraftPath() + sep + rstfile + ".xml";
   } else {
-    resetDef = rstfile;
+    init_file_name = rstfile;
   }
 
-  document = LoadXMLDocument(resetDef);
+  document = LoadXMLDocument(init_file_name);
+
+  // Make sure that the document is valid
+  if (!document) {
+    cerr << "File: " << init_file_name << " could not be read." << endl;
+    exit(-1);
+  }
 
   if (document->GetName() != string("initialize")) {
-    cerr << "File: " << resetDef << " is not a reset file" << endl;
+    cerr << "File: " << init_file_name << " is not a reset file." << endl;
     exit(-1);
   }
 
-  if (document->FindElement("ubody"))
-    SetUBodyFpsIC(document->FindElementValueAsNumberConvertTo("ubody", "FT/SEC"));
-  if (document->FindElement("vbody"))
-    SetVBodyFpsIC(document->FindElementValueAsNumberConvertTo("vbody", "FT/SEC"));
-  if (document->FindElement("wbody"))
-    SetWBodyFpsIC(document->FindElementValueAsNumberConvertTo("wbody", "FT/SEC"));
   if (document->FindElement("latitude"))
     SetLatitudeDegIC(document->FindElementValueAsNumberConvertTo("latitude", "DEG"));
   if (document->FindElement("longitude"))
     SetLongitudeDegIC(document->FindElementValueAsNumberConvertTo("longitude", "DEG"));
   if (document->FindElement("altitude"))
     SetAltitudeFtIC(document->FindElementValueAsNumberConvertTo("altitude", "FT"));
+  if (document->FindElement("ubody"))
+    SetUBodyFpsIC(document->FindElementValueAsNumberConvertTo("ubody", "FT/SEC"));
+  if (document->FindElement("vbody"))
+    SetVBodyFpsIC(document->FindElementValueAsNumberConvertTo("vbody", "FT/SEC"));
+  if (document->FindElement("wbody"))
+    SetWBodyFpsIC(document->FindElementValueAsNumberConvertTo("wbody", "FT/SEC"));
+  if (document->FindElement("vnorth"))
+    SetVNorthFpsIC(document->FindElementValueAsNumberConvertTo("vnorth", "FT/SEC"));
+  if (document->FindElement("veast"))
+    SetVEastFpsIC(document->FindElementValueAsNumberConvertTo("veast", "FT/SEC"));
+  if (document->FindElement("vdown"))
+    SetVDownFpsIC(document->FindElementValueAsNumberConvertTo("vdown", "FT/SEC"));
   if (document->FindElement("winddir"))
     SetWindDirDegIC(document->FindElementValueAsNumberConvertTo("winddir", "DEG"));
   if (document->FindElement("vwind"))
-    SetWindMagKtsIC(document->FindElementValueAsNumberConvertTo("vwind", "FT/SEC"));
+    SetWindMagKtsIC(document->FindElementValueAsNumberConvertTo("vwind", "KTS"));
   if (document->FindElement("hwind"))
     SetHeadWindKtsIC(document->FindElementValueAsNumberConvertTo("hwind", "KTS"));
   if (document->FindElement("xwind"))
     SetCrossWindKtsIC(document->FindElementValueAsNumberConvertTo("xwind", "KTS"));
   if (document->FindElement("vc"))
-    SetVcalibratedKtsIC(document->FindElementValueAsNumberConvertTo("vc", "FT/SEC"));
+    SetVcalibratedKtsIC(document->FindElementValueAsNumberConvertTo("vc", "KTS"));
+  if (document->FindElement("vt"))
+    SetVtrueKtsIC(document->FindElementValueAsNumberConvertTo("vt", "KTS"));
   if (document->FindElement("mach"))
     SetMachIC(document->FindElementValueAsNumber("mach"));
   if (document->FindElement("phi"))
@@ -791,15 +911,19 @@ bool FGInitialCondition::Load(string rstfile, bool useStoredPath)
   if (document->FindElement("roc"))
     SetClimbRateFpsIC(document->FindElementValueAsNumberConvertTo("roc", "FT/SEC"));
   if (document->FindElement("vground"))
-    SetVgroundKtsIC(document->FindElementValueAsNumberConvertTo("vground", "FT/SEC"));
-  if (document->FindElement("running")) {
-    n = int(document->FindElementValueAsNumber("running"));
-    if (n != 0) {
-      FGPropulsion* propulsion = fdmex->GetPropulsion();
-      for(unsigned int i=0; i<propulsion->GetNumEngines(); i++) {
-         propulsion->GetEngine(i)->SetRunning(true);
-      }
-    }
+    SetVgroundKtsIC(document->FindElementValueAsNumberConvertTo("vground", "KTS"));
+  if (document->FindElement("targetNlf"))
+  {
+    SetTargetNlfIC(document->FindElementValueAsNumber("targetNlf"));
+  }
+
+  // Check to see if any engines are specified to be initialized in a running state
+  FGPropulsion* propulsion = fdmex->GetPropulsion();
+  Element* running_elements = document->FindElement("running");
+  while (running_elements) {
+    n = int(running_elements->GetDataAsNumber());
+    propulsion->InitRunning(n);
+    running_elements = document->FindNextElement("running");
   }
 
   fdmex->RunIC();
@@ -923,7 +1047,18 @@ void FGInitialCondition::bind(void){
                        &FGInitialCondition::GetWBodyFpsIC,
                        &FGInitialCondition::SetWBodyFpsIC,
                        true);
-
+  PropertyManager->Tie("ic/vn-fps", this,
+                       &FGInitialCondition::GetVNorthFpsIC,
+                       &FGInitialCondition::SetVNorthFpsIC,
+                       true);
+  PropertyManager->Tie("ic/ve-fps", this,
+                       &FGInitialCondition::GetVEastFpsIC,
+                       &FGInitialCondition::SetVEastFpsIC,
+                       true);
+  PropertyManager->Tie("ic/vd-fps", this,
+                       &FGInitialCondition::GetVDownFpsIC,
+                       &FGInitialCondition::SetVDownFpsIC,
+                       true);
   PropertyManager->Tie("ic/gamma-rad", this,
                        &FGInitialCondition::GetFlightPathAngleRadIC,
                        &FGInitialCondition::SetFlightPathAngleRadIC,
@@ -967,58 +1102,11 @@ void FGInitialCondition::bind(void){
                        &FGInitialCondition::SetRRadpsIC,
                        true);
 
-}
-
-//******************************************************************************
-
-void FGInitialCondition::unbind(void)
-{
-  PropertyManager->Untie("ic/vc-kts");
-  PropertyManager->Untie("ic/ve-kts");
-  PropertyManager->Untie("ic/vg-kts");
-  PropertyManager->Untie("ic/vt-kts");
-  PropertyManager->Untie("ic/mach");
-  PropertyManager->Untie("ic/roc-fpm");
-  PropertyManager->Untie("ic/gamma-deg");
-  PropertyManager->Untie("ic/alpha-deg");
-  PropertyManager->Untie("ic/beta-deg");
-  PropertyManager->Untie("ic/theta-deg");
-  PropertyManager->Untie("ic/phi-deg");
-  PropertyManager->Untie("ic/psi-true-deg");
-  PropertyManager->Untie("ic/lat-gc-deg");
-  PropertyManager->Untie("ic/long-gc-deg");
-  PropertyManager->Untie("ic/h-sl-ft");
-  PropertyManager->Untie("ic/h-agl-ft");
-  PropertyManager->Untie("ic/sea-level-radius-ft");
-  PropertyManager->Untie("ic/terrain-altitude-ft");
-  PropertyManager->Untie("ic/vg-fps");
-  PropertyManager->Untie("ic/vt-fps");
-  PropertyManager->Untie("ic/vw-bx-fps");
-  PropertyManager->Untie("ic/vw-by-fps");
-  PropertyManager->Untie("ic/vw-bz-fps");
-  PropertyManager->Untie("ic/vw-north-fps");
-  PropertyManager->Untie("ic/vw-east-fps");
-  PropertyManager->Untie("ic/vw-down-fps");
-  PropertyManager->Untie("ic/vw-mag-fps");
-  PropertyManager->Untie("ic/vw-dir-deg");
-
-  PropertyManager->Untie("ic/roc-fps");
-
-  PropertyManager->Untie("ic/u-fps");
-  PropertyManager->Untie("ic/v-fps");
-  PropertyManager->Untie("ic/w-fps");
-
-  PropertyManager->Untie("ic/gamma-rad");
-  PropertyManager->Untie("ic/alpha-rad");
-  PropertyManager->Untie("ic/theta-rad");
-  PropertyManager->Untie("ic/beta-rad");
-  PropertyManager->Untie("ic/phi-rad");
-  PropertyManager->Untie("ic/psi-true-rad");
-  PropertyManager->Untie("ic/lat-gc-rad");
-  PropertyManager->Untie("ic/long-gc-rad");
-  PropertyManager->Untie("ic/p-rad_sec");
-  PropertyManager->Untie("ic/q-rad_sec");
-  PropertyManager->Untie("ic/r-rad_sec");
+  typedef int (FGInitialCondition::*iPMF)(void) const;
+  PropertyManager->Tie("simulation/write-state-file",
+                       this,
+                       (iPMF)0,
+                       &FGInitialCondition::WriteStateFile);
 
 }
 
index 105297c1a6e0c807511f327f110dd313694f5403..3723508bddaec6c4d2e671bcba7efb5f1548a7c6 100644 (file)
@@ -78,7 +78,7 @@ CLASS DOCUMENTATION
     very dynamic state (unless, of course, you have chosen your IC's wisely, or
     started on the ground) even after setting it up with this class.
 
-   <h2>Usage Notes</h2>
+   <h3>Usage Notes</h3>
 
    With a valid object of FGFDMExec and an aircraft model loaded:
 
@@ -96,7 +96,7 @@ CLASS DOCUMENTATION
    FDMExec->RunIC(fgic)
    @endcode
 
-   <h2>Speed</h2>
+   <h3>Speed</h3>
 
    Since vc, ve, vt, and mach all represent speed, the remaining
    three are recalculated each time one of them is set (using the
@@ -106,7 +106,7 @@ CLASS DOCUMENTATION
    components forces a recalculation of vt and vt then becomes the
    most recent speed set.
 
-   <h2>Alpha,Gamma, and Theta</h2>
+   <h3>Alpha,Gamma, and Theta</h3>
 
    This class assumes that it will be used to set up the sim for a
    steady, zero pitch rate condition. Since any two of those angles
@@ -128,6 +128,9 @@ CLASS DOCUMENTATION
    - ubody (velocity, ft/sec)
    - vbody (velocity, ft/sec)
    - wbody (velocity, ft/sec)
+   - vnorth (velocity, ft/sec)
+   - veast (velocity, ft/sec)
+   - vdown (velocity, ft/sec)
    - latitude (position, degrees)
    - longitude (position, degrees)
    - phi (orientation, degrees)
@@ -147,7 +150,7 @@ CLASS DOCUMENTATION
    - vground (ground speed, ft/sec)
    - running (0 or 1)
 
-   <h2>Properties</h2>
+   <h3>Properties</h3>
    @property ic/vc-kts (read/write) Calibrated airspeed initial condition in knots
    @property ic/ve-kts (read/write) Knots equivalent airspeed initial condition
    @property ic/vg-kts (read/write) Ground speed initial condition in knots
@@ -180,6 +183,9 @@ CLASS DOCUMENTATION
    @property ic/u-fps (read/write) Body frame x-axis velocity initial condition in feet/second
    @property ic/v-fps (read/write) Body frame y-axis velocity initial condition in feet/second
    @property ic/w-fps (read/write) Body frame z-axis velocity initial condition in feet/second
+   @property ic/vn-fps (read/write) Local frame x-axis (north) velocity initial condition in feet/second
+   @property ic/ve-fps (read/write) Local frame y-axis (east) velocity initial condition in feet/second
+   @property ic/vd-fps (read/write) Local frame z-axis (down) velocity initial condition in feet/second
    @property ic/gamma-rad (read/write) Flight path angle initial condition in radians
    @property ic/alpha-rad (read/write) Angle of attack initial condition in radians
    @property ic/theta-rad (read/write) Pitch angle initial condition in radians
@@ -240,6 +246,13 @@ public:
       @param theta Theta (pitch) angle in degrees */
   inline void SetThetaDegIC(double theta) { SetThetaRadIC(theta*degtorad); }
 
+  /** Resets the IC data structure to new values
+      @param u, v, w, ... **/
+  void ResetIC(double u0, double v0, double w0, double p0, double q0, double r0,
+               double alpha0, double beta0, double phi0, double theta0, double psi0,
+               double latitudeRad0, double longitudeRad0, double altitudeAGL0,
+               double gamma0);
+
   /** Sets the roll angle initial condition in degrees.
       @param phi roll angle in degrees */
   inline void SetPhiDegIC(double phi)  { SetPhiRadIC(phi*degtorad);}
@@ -374,15 +387,15 @@ public:
 
   /** Sets the initial local axis north velocity.
       @param vn Initial north velocity in feet/second */
-  void SetVnorthFpsIC(double vn);
+  void SetVNorthFpsIC(double vn);
 
   /** Sets the initial local axis east velocity.
       @param ve Initial east velocity in feet/second */
-  void SetVeastFpsIC(double ve);
+  void SetVEastFpsIC(double ve);
 
   /** Sets the initial local axis down velocity.
       @param vd Initial down velocity in feet/second */
-  void SetVdownFpsIC(double vd);
+  void SetVDownFpsIC(double vd);
 
   /** Sets the initial roll rate.
       @param P Initial roll rate in radians/second */
@@ -482,6 +495,18 @@ public:
       @return Initial body axis Z velocity in feet/second. */
   double GetWBodyFpsIC(void) const;
 
+  /** Gets the initial local frame X (North) velocity.
+      @return Initial local frame X (North) axis velocity in feet/second. */
+  double GetVNorthFpsIC(void) const {return vnorth;};
+
+  /** Gets the initial local frame Y (East) velocity.
+      @return Initial local frame Y (East) axis velocity in feet/second. */
+  double GetVEastFpsIC(void) const {return veast;};
+
+  /** Gets the initial local frame Z (Down) velocity.
+      @return Initial local frame Z (Down) axis velocity in feet/second. */
+  double GetVDownFpsIC(void) const {return vdown;};
+
   /** Gets the initial body axis roll rate.
       @return Initial body axis roll rate in radians/second */
   double GetPRadpsIC() const { return p; }
@@ -526,6 +551,10 @@ public:
       @param lon Initial longitude in radians */
   inline void SetLongitudeRadIC(double lon) { longitude=lon; }
 
+  /** Sets the target normal load factor.
+      @param nlf Normal load factor*/
+  inline void SetTargetNlfIC(double nlf) { targetNlfIC=nlf; }
+
   /** Gets the initial flight path angle.
       @return Initial flight path angle in radians */
   inline double GetFlightPathAngleRadIC(void) const { return gamma; }
@@ -566,12 +595,24 @@ public:
       @return Initial windset */
   inline windset GetWindSet(void) { return lastWindSet; }
 
+  /** Gets the target normal load factor set from IC.
+      @return target normal load factor set from IC*/
+  inline double GetTargetNlfIC(void) { return targetNlfIC; }
+
   /** Loads the initial conditions.
       @param rstname The name of an initial conditions file
       @param useStoredPath true if the stored path to the IC file should be used
       @return true if successful */
   bool Load(string rstname, bool useStoredPath = true );
 
+  /** Get init-file name
+  */
+  string GetInitFile(void) {return init_file_name;}
+  /** Set init-file name
+  */
+  void SetInitFile(string f) { init_file_name = f;}
+  void WriteStateFile(int num);
+
 private:
   double vt,vc,ve,vg;
   double mach;
@@ -586,6 +627,7 @@ private:
   double sea_level_radius;
   double terrain_altitude;
   double radius_to_vehicle;
+  double targetNlfIC;
 
   double  alpha, beta, theta, phi, psi, gamma;
   double salpha,sbeta,stheta,sphi,spsi,sgamma;
@@ -607,6 +649,7 @@ private:
   bool getMachFromVcas(double *Mach,double vcas);
 
   double GammaEqOfTheta(double Theta);
+  void InitializeIC(void);
   double GammaEqOfAlpha(double Alpha);
   double calcVcas(double Mach);
   void calcUVWfromNED(void);
@@ -615,8 +658,9 @@ private:
   bool findInterval(double x,double guess);
   bool solve(double *y, double x);
   void bind(void);
-  void unbind(void);
   void Debug(int from);
+
+  string init_file_name;
 };
 }
 #endif
index 854519c618ac820374d3779f0fd9cd530deb9583..8979f9e3b887a143a90e1086e7bd2c1fc12acb23 100644 (file)
@@ -80,7 +80,7 @@ FGTrim::FGTrim(FGFDMExec *FDMExec,TrimMode tt) {
   fgic=fdmex->GetIC();
   total_its=0;
   trimudot=true;
-  gamma_fallback=true;
+  gamma_fallback=false;
   axis_count=0;
   mode=tt;
   xlo=xhi=alo=ahi=0.0;
@@ -633,7 +633,7 @@ void FGTrim::SetMode(TrimMode tt) {
         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,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 ));
index a0236a2d7c70500a3d3a4d49915ea2cc79280f8d..8976d7a525d3c59ccc4fceb19148b5309b7cd746 100644 (file)
@@ -41,7 +41,14 @@ namespace JSBSim {
 
 FGGroundCallback::FGGroundCallback()
 {
-  mReferenceRadius = 20925650.0;
+  mReferenceRadius = 20925650.0; // Sea level radius
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGGroundCallback::FGGroundCallback(double ReferenceRadius)
+{
+  mReferenceRadius = ReferenceRadius;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index 0a5a7af67aa70a9911e9ca14179cf65e1c2ae3ea..bb36e650c6581369345a90e043e88a240459d576 100644 (file)
@@ -69,7 +69,16 @@ CLASS DECLARATION
 class FGGroundCallback : public FGJSBBase
 {
 public:
+  /** Default constructor.
+  Within this constructor, the reference radius is set to the WGS84 equatorial
+  radius. This constructor should really not be called, instead relying on the 
+  constructor that takes reference radius as an argument. */
   FGGroundCallback();
+
+  /** Constructor
+  This constructor accepts the reference radius in feet. This is the preferred  
+  constructor. */
+  FGGroundCallback(double ReferenceRadius);
   virtual ~FGGroundCallback();
 
   /** Compute the altitude above sealevel. */
@@ -77,6 +86,8 @@ public:
   /** Compute the altitude above ground. Defaults to sealevel altitude. */
   virtual double GetAGLevel(double t, const FGLocation& l, FGLocation& cont,
                             FGColumnVector3& n, FGColumnVector3& v) const;
+  virtual void SetTerrainGeoCentRadius(double radius) {mReferenceRadius = radius;}
+  virtual double GetTerrainGeoCentRadius(void) const {return mReferenceRadius;}
 private:
   /// Reference radius.
   double mReferenceRadius;
index 1f6f6d2e29eaedc4dda6921da195554cdbaae480..cf36fddc97a83651681d080ad8be6827fba79bbf 100755 (executable)
@@ -78,9 +78,9 @@ FGPropertyManager*
 FGPropertyManager::GetNode (const string &path, bool create)
 {
   SGPropertyNode* node=this->getNode(path.c_str(), create);
-  if (node == 0 && !suppress_warning)
-    cout << "FGPropertyManager::GetNode() No node found for "
-         << path << endl;
+  if (node == 0 && !suppress_warning) {
+    cout << "FGPropertyManager::GetNode() No node found for " << path << endl;
+  }
   return (FGPropertyManager*)node;
 }
 
index 40754780ecffa2f81f035e796221f9b5d7d178fa..4e3b5626ab4ee353ed236b9541cd460045be52c4 100644 (file)
@@ -37,7 +37,11 @@ INCLUDES
 
 #include <string>
 #include <iostream>
-#include "simgear/props/props.hxx"
+#ifdef FGFS
+#  include <simgear/props/props.hxx>
+#else
+#  include "simgear/props/props.hxx"
+#endif
 
 #include "FGJSBBase.h"
 
@@ -51,10 +55,9 @@ DEFINITIONS
 FORWARD DECLARATIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
+using namespace std;
+
 namespace JSBSim {
-  using std::cout;
-  using std::string;
-  using std::endl;
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 CLASS DOCUMENTATION
@@ -561,7 +564,7 @@ class FGPropertyManager : public SGPropertyNode, public FGJSBBase
      * @param setter The object's setter method, or 0 if the value is
      *        unmodifiable.
      * @param useDefault true if the setter should be invoked with any existing
-     *        property value should be; false if the old value should be
+     *        property value should there be one; false if the old value should be
      *        discarded; defaults to true.
      */
     template <class T, class V> inline void
index 7e542fbe9a130f52b5253f9561518f9a5e947ff4..0d032fbde33422810e56cd993028172c54174f29 100755 (executable)
@@ -85,13 +85,13 @@ FGScript::FGScript(FGFDMExec* fgex) : FDMExec(fgex)
 FGScript::~FGScript()
 {
   unsigned int i;
-  for (i=0; i<local_properties.size(); i++)
-    PropertyManager->Untie(local_properties[i]->title);
-  
-  for (i=0; i<local_properties.size(); i++)
-    delete local_properties[i];
 
+  for (i=0; i<local_properties.size(); i++) delete local_properties[i];
   local_properties.clear();
+
+  for (i=0; i<Events.size(); i++) delete Events[i].Condition;
+  Events.clear();
+
   Debug(1);
 }
 
@@ -105,6 +105,8 @@ bool FGScript::LoadScript( string script )
   Element *condition_element=0, *set_element=0, *delay_element=0;
   Element *notify_element = 0L, *notify_property_element = 0L;
   Element *property_element = 0L;
+  Element *output_element = 0L;
+  Element *input_element = 0L;
   bool result = false;
   double dt = 0.0, value = 0.0;
   struct event *newEvent;
@@ -112,6 +114,16 @@ bool FGScript::LoadScript( string script )
 
   document = LoadXMLDocument(script);
 
+  if (!document) {
+    cerr << "File: " << script << " could not be loaded." << endl;
+    return false;
+  }
+
+  // Set up input and output files if specified
+  
+  output_element = document->FindElement("output");
+  input_element = document->FindElement("input");
+
   if (document->GetName() != string("runscript")) {
     cerr << "File: " << script << " is not a script file" << endl;
     return false;
@@ -135,7 +147,7 @@ bool FGScript::LoadScript( string script )
   EndTime   = run_element->GetAttributeValueAsNumber("end");
   dt        = run_element->GetAttributeValueAsNumber("dt");
   State->Setdt(dt);
-
+  
   // read aircraft and initialization files
 
   element = document->FindElement("use");
@@ -160,12 +172,33 @@ bool FGScript::LoadScript( string script )
     return false;
   }
 
-  // Read local property declarations
+  // Now, read input spec if given.
+  if (input_element > 0) {
+    FDMExec->GetInput()->Load(input_element);
+  }
+
+  // Now, read output spec if given.
+  if (output_element > 0) {
+    string output_file = output_element->GetAttributeValue("file");
+    if (output_file.empty()) {
+      cerr << "No logging directives file was specified." << endl;
+    } else {
+      FDMExec->SetOutputDirectives(output_file);
+    }
+  }
+
+  // Read local property/value declarations
   property_element = run_element->FindElement("property");
   while (property_element) {
-    LocalProps *localProp = new LocalProps();
+
+    double value=0.0;
+    if ( ! property_element->GetAttributeValue("value").empty())
+      value = property_element->GetAttributeValueAsNumber("value");
+
+    LocalProps *localProp = new LocalProps(value);
     localProp->title = property_element->GetDataLine();
     local_properties.push_back(localProp);
+
     PropertyManager->Tie(localProp->title, (local_properties.back())->value);
     property_element = run_element->FindNextElement("property");
   }
@@ -210,7 +243,14 @@ bool FGScript::LoadScript( string script )
       notify_property_element = notify_element->FindElement("property");
       while (notify_property_element) {
         notifyPropertyName = notify_property_element->GetDataLine();
-        newEvent->NotifyProperties.push_back( PropertyManager->GetNode(notifyPropertyName) );
+        if (PropertyManager->GetNode(notifyPropertyName)) {
+          newEvent->NotifyProperties.push_back( PropertyManager->GetNode(notifyPropertyName) );
+        } else {
+          cout << endl << fgred << "  Could not find the property named "
+               << notifyPropertyName << " in script" << endl << "  \""
+               << ScriptName << "\". This unknown property will not be "
+               << "echoed for notification." << reset << endl;
+        }
         notify_property_element = notify_element->FindNextElement("property");
       }
     }
@@ -220,7 +260,15 @@ bool FGScript::LoadScript( string script )
     while (set_element) {
       prop_name = set_element->GetAttributeValue("name");
       newEvent->SetParam.push_back( PropertyManager->GetNode(prop_name) );
-      value = set_element->GetAttributeValueAsNumber("value");
+      //Todo - should probably do some safety checking here to make sure one or the other
+      //of value or function is specified.
+      if (!set_element->GetAttributeValue("value").empty()) {
+        value = set_element->GetAttributeValueAsNumber("value");
+        newEvent->Functions.push_back((FGFunction*)0L);
+      } else if (set_element->FindElement("function")) {
+        value = 0.0;
+        newEvent->Functions.push_back(new FGFunction(PropertyManager, set_element->FindElement("function")));
+      }
       newEvent->SetValue.push_back(value);
       newEvent->OriginalValue.push_back(0.0);
       newEvent->newValue.push_back(0.0);
@@ -246,6 +294,8 @@ bool FGScript::LoadScript( string script )
       set_element = event_element->FindNextElement("set");
     }
     Events.push_back(*newEvent);
+    delete newEvent;
+
     event_element = run_element->FindNextElement("event");
   }
 
@@ -284,6 +334,9 @@ bool FGScript::RunScript(void)
         // The conditions are true, do the setting of the desired Event parameters
         for (i=0; i<iEvent->SetValue.size(); i++) {
           iEvent->OriginalValue[i] = iEvent->SetParam[i]->getDoubleValue();
+          if (iEvent->Functions[i] != 0) { // Parameter should be set to a function value
+            iEvent->SetValue[i] = iEvent->Functions[i]->GetValue();
+          }
           switch (iEvent->Type[i]) {
           case FG_VALUE:
           case FG_BOOL:
@@ -312,25 +365,29 @@ bool FGScript::RunScript(void)
       for (i=0; i<iEvent->SetValue.size(); i++) {
         if (iEvent->Transiting[i]) {
           iEvent->TimeSpan = currentTime - iEvent->StartTime;
-          switch (iEvent->Action[i]) {
-          case FG_RAMP:
-            if (iEvent->TimeSpan <= iEvent->TC[i]) {
-              newSetValue = iEvent->TimeSpan/iEvent->TC[i] * iEvent->ValueSpan[i] + iEvent->OriginalValue[i];
-            } else {
+          if (iEvent->Functions[i] == 0) {
+            switch (iEvent->Action[i]) {
+            case FG_RAMP:
+              if (iEvent->TimeSpan <= iEvent->TC[i]) {
+                newSetValue = iEvent->TimeSpan/iEvent->TC[i] * iEvent->ValueSpan[i] + iEvent->OriginalValue[i];
+              } else {
+                newSetValue = iEvent->newValue[i];
+                iEvent->Transiting[i] = false;
+              }
+              break;
+            case FG_STEP:
               newSetValue = iEvent->newValue[i];
               iEvent->Transiting[i] = false;
+              break;
+            case FG_EXP:
+              newSetValue = (1 - exp( -iEvent->TimeSpan/iEvent->TC[i] )) * iEvent->ValueSpan[i] + iEvent->OriginalValue[i];
+              break;
+            default:
+              cerr << "Invalid Action specified" << endl;
+              break;
             }
-            break;
-          case FG_STEP:
-            newSetValue = iEvent->newValue[i];
-            iEvent->Transiting[i] = false;
-            break;
-          case FG_EXP:
-            newSetValue = (1 - exp( -iEvent->TimeSpan/iEvent->TC[i] )) * iEvent->ValueSpan[i] + iEvent->OriginalValue[i];
-            break;
-          default:
-            cerr << "Invalid Action specified" << endl;
-            break;
+          } else { // Set the new value based on a function
+            newSetValue = iEvent->Functions[i]->GetValue();
           }
           iEvent->SetParam[i]->setDoubleValue(newSetValue);
         }
@@ -403,8 +460,27 @@ void FGScript::Debug(int from)
 
         cout << endl << "  Actions taken:" << endl << "    {";
         for (unsigned j=0; j<Events[i].SetValue.size(); j++) {
-          cout << endl << "      set " << Events[i].SetParam[j]->GetName()
-               << " to " << Events[i].SetValue[j];
+          if (Events[i].SetValue[j] == 0.0 && Events[i].Functions[j] != 0L) {
+            if (Events[i].SetParam[j] == 0) {
+              cerr << fgred << highint << endl
+                   << "  An attempt has been made to access a non-existent property" << endl
+                   << "  in this event. Please check the property names used, spelling, etc."
+                   << reset << endl;
+              exit(-1);
+            }
+            cout << endl << "      set " << Events[i].SetParam[j]->GetName()
+                 << " to function value";
+          } else {
+            if (Events[i].SetParam[j] == 0) {
+              cerr << fgred << highint << endl
+                   << "  An attempt has been made to access a non-existent property" << endl
+                   << "  in this event. Please check the property names used, spelling, etc."
+                   << reset << endl;
+              exit(-1);
+            }
+            cout << endl << "      set " << Events[i].SetParam[j]->GetName()
+                 << " to " << Events[i].SetValue[j];
+          }
 
           switch (Events[i].Type[j]) {
           case FG_VALUE:
index 4915404756fa7638da0b99e8c0ab458b7258f25d..f1a09bf1ff3104bfb5d73ea888e23e025ebbfd66 100644 (file)
@@ -40,6 +40,7 @@ INCLUDES
 #include "FGJSBBase.h"
 #include "FGState.h"
 #include "FGFDMExec.h"
+#include <math/FGFunction.h>
 #include <math/FGCondition.h>
 #include <vector>
 #include <input_output/FGXMLFileRead.h>
@@ -183,6 +184,10 @@ public:
       @return false if script should exit (i.e. if time limits are violated */
   bool RunScript(void);
 
+  void ResetEvents(void) {
+    for (int i=0; i<Events.size(); i++) Events[i].reset();
+  }
+
 private:
   enum eAction {
     FG_RAMP  = 1,
@@ -217,6 +222,7 @@ private:
     vector <double>  OriginalValue;
     vector <double>  ValueSpan;
     vector <bool>    Transiting;
+    vector <FGFunction*> Functions;
 
     event() {
       Triggered = false;
@@ -228,13 +234,20 @@ private:
       StartTime = 0.0;
       TimeSpan = 0.0;
     }
+
+    void reset(void) {
+      Triggered = false;
+      PrevTriggered = false;
+      Notified = false;
+      StartTime = 0.0;
+    }
   };
 
   struct LocalProps {
     double *value;
     string title;
-    LocalProps() {
-      value = new double(0.0);
+    LocalProps(double initial_value=0) {
+      value = new double(initial_value);
       title = "";
     }
   };
index 741a806095ac292e16d1a59b25ebc55ab65e480c..a32ce27c7d9bce27c2ac49a4dfec3bae10a07b9c 100755 (executable)
@@ -73,61 +73,134 @@ Element::Element(string nm)
   element_index = 0;
 
   // convert ["from"]["to"] = factor, so: from * factor = to
+  // Length
   convert["M"]["FT"] = 3.2808399;
   convert["FT"]["M"] = 1.0/convert["M"]["FT"];
-  convert["M2"]["FT2"] = convert["M"]["FT"]*convert["M"]["FT"];
-  convert["FT2"]["M2"] = 1.0/convert["M2"]["FT2"];
   convert["FT"]["IN"] = 12.0;
   convert["IN"]["FT"] = 1.0/convert["FT"]["IN"];
+  convert["IN"]["M"] = convert["IN"]["FT"] * convert["FT"]["M"];
+  convert["M"]["IN"] = convert["M"]["FT"] * convert["FT"]["IN"];
+  // Area
+  convert["M2"]["FT2"] = convert["M"]["FT"]*convert["M"]["FT"];
+  convert["FT2"]["M2"] = 1.0/convert["M2"]["FT2"];
+  convert["M2"]["IN2"] = convert["M"]["IN"]*convert["M"]["IN"];
+  convert["IN2"]["M2"] = 1.0/convert["M2"]["IN2"];
+  // Volume
+  convert["IN3"]["CC"] = 16.387064;
+  convert["CC"]["IN3"] = 1.0/convert["IN3"]["CC"];
+  convert["FT3"]["IN3"] = 1728.0;
+  convert["IN3"]["FT3"] = 1.0/convert["FT3"]["IN3"];
+  convert["M3"]["FT3"] = 35.3146667;
+  convert["FT3"]["M3"] = 1.0/convert["M3"]["FT3"];
+  convert["LTR"]["IN3"] = 61.0237441;
+  convert["IN3"]["LTR"] = 1.0/convert["LTR"]["IN3"];
+  // Mass & Weight
   convert["LBS"]["KG"] = 0.45359237;
   convert["KG"]["LBS"] = 1.0/convert["LBS"]["KG"];
+  convert["SLUG"]["KG"] = 14.59390;
+  convert["KG"]["SLUG"] = 1.0/convert["SLUG"]["KG"];
+  // Moments of Inertia
   convert["SLUG*FT2"]["KG*M2"] = 1.35594;
   convert["KG*M2"]["SLUG*FT2"] = 1.0/convert["SLUG*FT2"]["KG*M2"];
+  // Angles
   convert["RAD"]["DEG"] = 360.0/(2.0*3.1415926);
   convert["DEG"]["RAD"] = 1.0/convert["RAD"]["DEG"];
+  // Spring force
   convert["LBS/FT"]["N/M"] = 14.5939;
-  convert["LBS/FT/SEC"]["N/M/SEC"] = 14.5939;
   convert["N/M"]["LBS/FT"] = 1.0/convert["LBS/FT"]["N/M"];
+  // Damping force
+  convert["LBS/FT/SEC"]["N/M/SEC"] = 14.5939;
   convert["N/M/SEC"]["LBS/FT/SEC"] = 1.0/convert["LBS/FT/SEC"]["N/M/SEC"];
+  // Power
   convert["WATTS"]["HP"] = 0.001341022;
   convert["HP"]["WATTS"] = 1.0/convert["WATTS"]["HP"];
+  // Force
   convert["N"]["LBS"] = 0.22482;
   convert["LBS"]["N"] = 1.0/convert["N"]["LBS"];
+  // Velocity
   convert["KTS"]["FT/SEC"] = 1.68781;
   convert["FT/SEC"]["KTS"] = 1.0/convert["KTS"]["FT/SEC"];
+  convert["M/S"]["FT/S"] = 3.2808399;
+  convert["FT/S"]["M/S"] = 1.0/convert["M/S"]["FT/S"];
+  // Torque
   convert["FT*LBS"]["N*M"] = 1.35581795;
   convert["N*M"]["FT*LBS"] = 1/convert["FT*LBS"]["N*M"];
-  convert["IN"]["M"] = convert["IN"]["FT"] * convert["FT"]["M"];
-  convert["M"]["IN"] = convert["M"]["FT"] * convert["FT"]["IN"];
-
+  // Valve
+  convert["M4*SEC/KG"]["FT4*SEC/SLUG"] = convert["M"]["FT"]*convert["M"]["FT"]*
+    convert["M"]["FT"]*convert["M"]["FT"]/convert["KG"]["SLUG"];
+  convert["FT4*SEC/SLUG"]["M4*SEC/KG"] =
+    1.0/convert["M4*SEC/KG"]["FT4*SEC/SLUG"];
+  // Pressure
+  convert["INHG"]["PSF"] = 70.7180803;
+  convert["PSF"]["INHG"] = 1.0/convert["INHG"]["PSF"];
+  convert["ATM"]["INHG"] = 29.9246899;
+  convert["INHG"]["ATM"] = 1.0/convert["ATM"]["INHG"];
+  convert["PSI"]["INHG"] = 2.03625437;
+  convert["INHG"]["PSI"] = 1.0/convert["PSI"]["INHG"];
+  convert["INHG"]["PA"] = 3386.0; // inches Mercury to pascals
+  convert["PA"]["INHG"] = 1.0/convert["INHG"]["PA"];
+  convert["LBS/FT2"]["N/M2"] = 14.5939/convert["FT"]["M"];
+  convert["N/M2"]["LBS/FT2"] = 1.0/convert["LBS/FT2"]["N/M2"];
+  convert["LBS/FT2"]["PA"] = convert["LBS/FT2"]["N/M2"];
+  convert["PA"]["LBS/FT2"] = 1.0/convert["LBS/FT2"]["PA"];
+  // Mass flow
+  convert["KG/MIN"]["LBS/MIN"] = convert["KG"]["LBS"];
+
+  // Length
   convert["M"]["M"] = 1.00;
   convert["FT"]["FT"] = 1.00;
   convert["IN"]["IN"] = 1.00;
-  convert["IN3"]["IN3"] = 1.00;
-  convert["DEG"]["DEG"] = 1.00;
-  convert["RAD"]["RAD"] = 1.00;
+  // Area
   convert["M2"]["M2"] = 1.00;
   convert["FT2"]["FT2"] = 1.00;
-  convert["KG*M2"]["KG*M2"] = 1.00;
-  convert["SLUG*FT2"]["SLUG*FT2"] = 1.00;
+  // Volume
+  convert["IN3"]["IN3"] = 1.00;
+  convert["CC"]["CC"] = 1.0;
+  convert["M3"]["M3"] = 1.0;
+  convert["FT3"]["FT3"] = 1.0;
+  convert["LTR"]["LTR"] = 1.0;
+  // Mass & Weight
   convert["KG"]["KG"] = 1.00;
   convert["LBS"]["LBS"] = 1.00;
+  // Moments of Inertia
+  convert["KG*M2"]["KG*M2"] = 1.00;
+  convert["SLUG*FT2"]["SLUG*FT2"] = 1.00;
+  // Angles
+  convert["DEG"]["DEG"] = 1.00;
+  convert["RAD"]["RAD"] = 1.00;
+  // Spring force
   convert["LBS/FT"]["LBS/FT"] = 1.00;
-  convert["LBS/SEC"]["LBS/SEC"] = 1.00;
-  convert["LBS/FT/SEC"]["LBS/FT/SEC"] = 1.00;
   convert["N/M"]["N/M"] = 1.00;
+  // Damping force
+  convert["LBS/FT/SEC"]["LBS/FT/SEC"] = 1.00;
   convert["N/M/SEC"]["N/M/SEC"] = 1.00;
-  convert["PSI"]["PSI"] = 1.00;
-  convert["PSF"]["PSF"] = 1.00;
-  convert["INHG"]["INHG"] = 1.00;
+  // Power
   convert["HP"]["HP"] = 1.00;
-  convert["N"]["N"] = 1.00;
   convert["WATTS"]["WATTS"] = 1.00;
-  convert["LBS/SEC"]["LBS/SEC"] = 1.00;
+  // Force
+  convert["N"]["N"] = 1.00;
+  // Velocity
   convert["FT/SEC"]["FT/SEC"] = 1.00;
   convert["KTS"]["KTS"] = 1.00;
+  convert["M/S"]["M/S"] = 1.0;
+  // Torque
   convert["FT*LBS"]["FT*LBS"] = 1.00;
   convert["N*M"]["N*M"] = 1.00;
+  // Valve
+  convert["M4*SEC/KG"]["M4*SEC/KG"] = 1.0;
+  convert["FT4*SEC/SLUG"]["FT4*SEC/SLUG"] = 1.0;
+  // Pressure
+  convert["PSI"]["PSI"] = 1.00;
+  convert["PSF"]["PSF"] = 1.00;
+  convert["INHG"]["INHG"] = 1.00;
+  convert["ATM"]["ATM"] = 1.0;
+  convert["PA"]["PA"] = 1.0;
+  convert["N/M2"]["N/M2"] = 1.00;
+  convert["LBS/FT2"]["LBS/FT2"] = 1.00;
+  // Mass flow
+  convert["LBS/SEC"]["LBS/SEC"] = 1.00;
+  convert["KG/MIN"]["KG/MIN"] = 1.0;
+  convert["LBS/MIN"]["LBS/MIN"] = 1.0;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -158,7 +231,7 @@ double Element::GetAttributeValueAsNumber(string attr)
 {
   string attribute = GetAttributeValue(attr);
 
-  if (attribute.empty()) return 99e99;
+  if (attribute.empty()) return HUGE_VAL;
   else return (atof(attribute.c_str()));
 }
 
@@ -203,9 +276,11 @@ double Element::GetDataAsNumber(void)
 {
   if (data_lines.size() == 1) {
     return atof(data_lines[0].c_str());
+  } else if (data_lines.size() == 0) {
+    return HUGE_VAL;
   } else {
-    cerr << "Attempting to get single data value from multiple lines" << endl;
-    return 0;
+    cerr << "Attempting to get single data value from multiple lines in element " << name << endl;
+    return HUGE_VAL;
   }
 }
 
index ce3711aed1e1a42e442bbb7d3bfc9f2484d6c80b..b30dfaf5361946028a485b527742cde34b00c99d 100755 (executable)
@@ -108,6 +108,7 @@ CLASS DOCUMENTATION
     - convert["N"]["LBS"] = 0.22482;
     - convert["LBS"]["N"] = 1.0/convert["N"]["LBS"];
     - convert["KTS"]["FT/SEC"] = ktstofps;
+    - convert["KG/MIN"]["LBS/MIN"] = convert["KG"]["LBS"];
 
     - convert["M"]["M"] = 1.00;
     - convert["FT"]["FT"] = 1.00;
@@ -131,6 +132,8 @@ CLASS DOCUMENTATION
     - convert["WATTS"]["WATTS"] = 1.00;
     - convert["KTS"]["KTS"] = 1.0;
     - convert["FT/SEC"]["FT/SEC"] = 1.0;
+    - convert["KG/MIN"]["KG/MIN"] = 1.0;
+    - convert["LBS/MIN"]["LBS/MIN"] = 1.0;
 
     Where:
     - N = newtons
@@ -141,6 +144,7 @@ CLASS DOCUMENTATION
     - FT = feet
     - FT2 = feet squared
     - SEC = seconds
+    - MIN = minutes
     - SLUG = slug
     - DEG = degrees
     - RAD = radians
index c1a582699ae7ae09ccd09e1813957385916a19c2..33ac21d26fb0892784e78cf46ae0c5d732bf89c0 100644 (file)
@@ -32,13 +32,12 @@ This class excapsulates a socket for simple data writing
 HISTORY
 --------------------------------------------------------------------------------
 11/08/99   JSB   Created
+11/08/07   HDW   Added Generic Socket Send
 
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 INCLUDES
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#include <cstring>
-
 #include "FGfdmSocket.h"
 
 namespace JSBSim {
@@ -50,6 +49,60 @@ static const char *IdHdr = ID_FDMSOCKET;
 CLASS IMPLEMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
+FGfdmSocket::FGfdmSocket(string address, int port, int protocol)
+{
+  sckt = sckt_in = size = 0;
+  connected = false;
+
+  #if defined(__BORLANDC__) || defined(_MSC_VER) || defined(__MINGW32__)
+    WSADATA wsaData;
+    int wsaReturnCode;
+    wsaReturnCode = WSAStartup(MAKEWORD(1,1), &wsaData);
+    if (wsaReturnCode == 0) cout << "Winsock DLL loaded ..." << endl;
+    else cout << "Winsock DLL not initialized ..." << endl;
+  #endif
+
+  if (address.find_first_not_of("0123456789.",0) != address.npos) {
+    if ((host = gethostbyname(address.c_str())) == NULL) {
+      cout << "Could not get host net address by name..." << endl;
+    }
+  } else {
+    if ((host = gethostbyaddr(address.c_str(), address.size(), PF_INET)) == NULL) {
+      cout << "Could not get host net address by number..." << endl;
+    }
+  }
+
+  if (host != NULL) {
+    if (protocol == ptUDP) {  //use udp protocol
+       sckt = socket(AF_INET, SOCK_DGRAM, 0);
+       cout << "Creating UDP socket on port " << port << endl;
+    }
+    else { //use tcp protocol
+       sckt = socket(AF_INET, SOCK_STREAM, 0);
+       cout << "Creating TCP socket on port " << port << endl;
+    }
+
+    if (sckt >= 0) {  // successful
+      memset(&scktName, 0, sizeof(struct sockaddr_in));
+      scktName.sin_family = AF_INET;
+      scktName.sin_port = htons(port);
+      memcpy(&scktName.sin_addr, host->h_addr_list[0], host->h_length);
+      int len = sizeof(struct sockaddr_in);
+      if (connect(sckt, (struct sockaddr*)&scktName, len) == 0) {   // successful
+        cout << "Successfully connected to socket for output ..." << endl;
+        connected = true;
+      } else {                // unsuccessful
+        cout << "Could not connect to socket for output ..." << endl;
+      }
+    } else {          // unsuccessful
+      cout << "Could not create socket for FDM output, error = " << errno << endl;
+    }
+  }
+  Debug(0);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 FGfdmSocket::FGfdmSocket(string address, int port)
 {
   sckt = sckt_in = size = 0;
@@ -63,6 +116,10 @@ FGfdmSocket::FGfdmSocket(string address, int port)
     else cout << "Winsock DLL not initialized ..." << endl;
   #endif
 
+  cout << "... Socket Configuration Sanity Check ..." << endl;
+  cout << "Host name...   " << address << ",  Port...  " << port << "." << endl;
+  cout << "Host name... (char)  " << address.c_str() << "." << endl;
+
   if (address.find_first_not_of("0123456789.",0) != address.npos) {
     if ((host = gethostbyname(address.c_str())) == NULL) {
       cout << "Could not get host net address by name..." << endl;
@@ -81,7 +138,7 @@ FGfdmSocket::FGfdmSocket(string address, int port)
       memset(&scktName, 0, sizeof(struct sockaddr_in));
       scktName.sin_family = AF_INET;
       scktName.sin_port = htons(port);
-      std::memcpy(&scktName.sin_addr, host->h_addr_list[0], host->h_length);
+      memcpy(&scktName.sin_addr, host->h_addr_list[0], host->h_length);
       int len = sizeof(struct sockaddr_in);
       if (connect(sckt, (struct sockaddr*)&scktName, len) == 0) {   // successful
         cout << "Successfully connected to socket for output ..." << endl;
@@ -115,7 +172,7 @@ FGfdmSocket::FGfdmSocket(int port)
   sckt = socket(AF_INET, SOCK_STREAM, 0);
 
   if (sckt >= 0) {  // successful
-    std::memset(&scktName, 0, sizeof(struct sockaddr_in));
+    memset(&scktName, 0, sizeof(struct sockaddr_in));
     scktName.sin_family = AF_INET;
     scktName.sin_port = htons(port);
     int len = sizeof(struct sockaddr_in);
@@ -294,6 +351,16 @@ void FGfdmSocket::Send(void)
   }
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGfdmSocket::Send(char *data, int length)
+{
+  if ((send(sckt,data,length,0)) <= 0) {
+    perror("send");
+  } else {
+  }
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index f1d41ef1bb8a4d6d38d4d1c2e8132c04d7134823..14330bfea4ecfca7a7d9471af35bee920d5b4630 100644 (file)
@@ -26,6 +26,7 @@
 HISTORY
 --------------------------------------------------------------------------------
 11/08/99   JSB   Created
+11/08/07   HDW   Added Generic Socket Send
 
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 SENTRY
@@ -113,9 +114,12 @@ class FGfdmSocket : public FGJSBBase
 {
 public:
   FGfdmSocket(string, int);
+  FGfdmSocket(string, int, int);
   FGfdmSocket(int);
   ~FGfdmSocket();
   void Send(void);
+  void Send(char *data, int length);
+
   string Receive(void);
   int Reply(string text);
   void Append(const string s) {Append(s.c_str());}
@@ -127,6 +131,8 @@ public:
   void Close(void);
   bool GetConnectStatus(void) {return connected;}
 
+  enum {ptUDP, ptTCP};
+
 private:
   int sckt;
   int sckt_in;
diff --git a/src/FDM/JSBSim/input_output/net_fdm.hxx b/src/FDM/JSBSim/input_output/net_fdm.hxx
new file mode 100644 (file)
index 0000000..4b4f197
--- /dev/null
@@ -0,0 +1,133 @@
+// net_fdm.hxx -- defines a common net I/O interface to the flight
+//                dynamics model
+//
+// Written by Curtis Olson - http://www.flightgear.org/~curt
+// Started September 2001.
+//
+// This file is in the Public Domain, and comes with no warranty.
+//
+// $Id$
+
+
+#ifndef _NET_FDM_HXX
+#define _NET_FDM_HXX
+
+
+#include <time.h> // time_t
+
+#ifdef _MSC_VER
+typedef unsigned long uint32_t;
+typedef long int32_t;
+#endif
+
+//--->>>#include <simgear/misc/stdint.hxx> //not required for JSBSim
+
+
+// NOTE: this file defines an external interface structure.  Due to
+// variability between platforms and architectures, we only used fixed
+// length types here.  Specifically, integer types can vary in length.
+// I am not aware of any platforms that don't use 4 bytes for float
+// and 8 bytes for double.
+
+const uint32_t FG_NET_FDM_VERSION = 24;
+
+
+// Define a structure containing the top level flight dynamics model
+// parameters
+
+class FGNetFDM {
+
+public:
+
+    enum {
+        FG_MAX_ENGINES = 4,
+        FG_MAX_WHEELS = 3,
+        FG_MAX_TANKS = 4
+    };
+
+    uint32_t version;          // increment when data values change
+    uint32_t padding;          // padding
+
+    // Positions
+    double longitude;          // geodetic (radians)
+    double latitude;           // geodetic (radians)
+    double altitude;           // above sea level (meters)
+    float agl;                 // above ground level (meters)
+    float phi;                 // roll (radians)
+    float theta;               // pitch (radians)
+    float psi;                 // yaw or true heading (radians)
+    float alpha;                // angle of attack (radians)
+    float beta;                 // side slip angle (radians)
+
+    // Velocities
+    float phidot;              // roll rate (radians/sec)
+    float thetadot;            // pitch rate (radians/sec)
+    float psidot;              // yaw rate (radians/sec)
+    float vcas;                        // calibrated airspeed
+    float climb_rate;          // feet per second
+    float v_north;              // north velocity in local/body frame, fps
+    float v_east;               // east velocity in local/body frame, fps
+    float v_down;               // down/vertical velocity in local/body frame, fps
+    float v_wind_body_north;    // north velocity in local/body frame
+                                // relative to local airmass, fps
+    float v_wind_body_east;     // east velocity in local/body frame
+                                // relative to local airmass, fps
+    float v_wind_body_down;     // down/vertical velocity in local/body
+                                // frame relative to local airmass, fps
+
+    // Accelerations
+    float A_X_pilot;           // X accel in body frame ft/sec^2
+    float A_Y_pilot;           // Y accel in body frame ft/sec^2
+    float A_Z_pilot;           // Z accel in body frame ft/sec^2
+
+    // Stall
+    float stall_warning;        // 0.0 - 1.0 indicating the amount of stall
+    float slip_deg;            // slip ball deflection
+
+    // Pressure
+    
+    // Engine status
+    uint32_t num_engines;           // Number of valid engines
+    uint32_t eng_state[FG_MAX_ENGINES];// Engine state (off, cranking, running)
+    float rpm[FG_MAX_ENGINES];      // Engine RPM rev/min
+    float fuel_flow[FG_MAX_ENGINES]; // Fuel flow gallons/hr
+    float fuel_px[FG_MAX_ENGINES];   // Fuel pressure psi
+    float egt[FG_MAX_ENGINES];      // Exhuast gas temp deg F
+    float cht[FG_MAX_ENGINES];      // Cylinder head temp deg F
+    float mp_osi[FG_MAX_ENGINES];    // Manifold pressure
+    float tit[FG_MAX_ENGINES];      // Turbine Inlet Temperature
+    float oil_temp[FG_MAX_ENGINES];  // Oil temp deg F
+    float oil_px[FG_MAX_ENGINES];    // Oil pressure psi
+
+    // Consumables
+    uint32_t num_tanks;                // Max number of fuel tanks
+    float fuel_quantity[FG_MAX_TANKS];
+
+    // Gear status
+    uint32_t num_wheels;
+    uint32_t wow[FG_MAX_WHEELS];
+    float gear_pos[FG_MAX_WHEELS];
+    float gear_steer[FG_MAX_WHEELS];
+    float gear_compression[FG_MAX_WHEELS];
+
+    // Environment
+    uint32_t cur_time;           // current unix time
+                                 // FIXME: make this uint64_t before 2038
+    int32_t warp;                // offset in seconds to unix time
+    float visibility;            // visibility in meters (for env. effects)
+
+    // Control surface positions (normalized values)
+    float elevator;
+    float elevator_trim_tab;
+    float left_flap;
+    float right_flap;
+    float left_aileron;
+    float right_aileron;
+    float rudder;
+    float nose_wheel;
+    float speedbrake;
+    float spoilers;
+};
+
+
+#endif // _NET_FDM_HXX
index 85e6bab227304a11ce6dec3df00ede9b7cca63f1..58af989ed5cc7e89537a0d760ac7233f525a102e 100644 (file)
@@ -65,15 +65,15 @@ INCLUDES
 #      include <math.h>
 #    else
 #      include <cmath>
+#      if !(defined(_MSC_VER) && _MSC_VER <= 1200)
+          using std::sqrt;
+#      endif
 #    endif
      using std::ostream;
      using std::istream;
      using std::cerr;
      using std::cout;
      using std::endl;
-#    if !(defined(_MSC_VER) && _MSC_VER <= 1200)
-       using std::sqrt;
-#    endif
 #  endif
    using std::string;
 #endif
@@ -96,7 +96,7 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** This class implements a 3 dimensional vector.
+/** This class implements a 3 element column vector.
     @author Jon S. Berndt, Tony Peden, et. al.
     @version $Id$
 */
@@ -155,8 +155,8 @@ public:
       @param idx the component index.
       Return the value of the matrix entry at the given index.
       Indices are counted starting with 1.
-      This function is just a shortcut for the @ref double
-      operator()(unsigned int idx) const function. It is
+      This function is just a shortcut for the <tt>double
+      operator()(unsigned int idx) const</tt> function. It is
       used internally to access the elements in a more convenient way.
       Note that the index given in the argument is unchecked.   */
   double Entry(unsigned int idx) const { return data[idx-1]; }
@@ -165,8 +165,8 @@ public:
       @param idx the component index.
       Return a reference to the vector entry at the given index.
       Indices are counted starting with 1.
-      This function is just a shortcut for the @ref double&
-      operator()(unsigned int idx) function. It is
+      This function is just a shortcut for the <tt>double&
+      operator()(unsigned int idx)</tt> function. It is
       used internally to access the elements in a more convenient way.
       Note that the index given in the argument is unchecked.   */
   double& Entry(unsigned int idx) { return data[idx-1]; }
@@ -213,7 +213,7 @@ public:
   FGColumnVector3 operator/(const double scalar) const;
 
   /** Cross product multiplication.
-      @param v vector to multiply with.
+      @param V vector to multiply with.
       @return The resulting vector from the cross product multiplication.
       Compute and return the cross product of the current vector with
       the given argument.   */
index e5cebbcb043397ff35bbad776023640fa2d3dae4..02bcdf7753189903f7dcca66f4b41638a1aa7344 100644 (file)
@@ -75,12 +75,12 @@ FGCondition::FGCondition(Element* element, FGPropertyManager* PropertyManager) :
 
   condition_element = element->GetElement();
   while (condition_element) {
-    conditions.push_back(FGCondition(condition_element, PropertyManager));
+    conditions.push_back(new FGCondition(condition_element, PropertyManager));
     condition_element = element->GetNextElement();
   }
   for (unsigned int i=0; i<element->GetNumDataLines(); i++) {
     string data = element->GetDataLine(i);
-    conditions.push_back(FGCondition(data, PropertyManager));
+    conditions.push_back(new FGCondition(data, PropertyManager));
   }
 
   Debug(0);
@@ -151,6 +151,8 @@ void FGCondition::InitializeConditionals(void)
 
 FGCondition::~FGCondition(void)
 {
+  for (unsigned int i=0; i<conditions.size(); i++) delete conditions[i];
+
   Debug(1);
 }
 
@@ -158,7 +160,6 @@ FGCondition::~FGCondition(void)
 
 bool FGCondition::Evaluate(void )
 {
-  vector <FGCondition>::iterator iConditions;
   bool pass = false;
   double compareValue;
 
@@ -166,19 +167,16 @@ bool FGCondition::Evaluate(void )
 
     if (Logic == eAND) {
 
-      iConditions = conditions.begin();
       pass = true;
-      while (iConditions < conditions.end()) {
-        if (!iConditions->Evaluate()) pass = false;
-        *iConditions++;
+      for (unsigned int i=0; i<conditions.size(); i++) {
+        if (!conditions[i]->Evaluate()) pass = false;
       }
 
     } else { // Logic must be eOR
 
       pass = false;
-      while (iConditions < conditions.end()) {
-        if (iConditions->Evaluate()) pass = true;
-        *iConditions++;
+      for (unsigned int i=0; i<conditions.size(); i++) {
+        if (conditions[i]->Evaluate()) pass = true;
       }
 
     }
@@ -222,7 +220,6 @@ bool FGCondition::Evaluate(void )
 
 void FGCondition::PrintCondition(void )
 {
-  vector <FGCondition>::iterator iConditions;
   string scratch;
 
   if (isGroup) {
@@ -242,12 +239,9 @@ void FGCondition::PrintCondition(void )
       cerr << "Unknown logic for test condition" << endl;
     }
 
-    iConditions = conditions.begin();
     cout << scratch << endl;
-    while (iConditions < conditions.end()) {
-      iConditions->PrintCondition();
-      *iConditions++;
-    }
+    for (unsigned int i=0; i<conditions.size(); i++) conditions[i]->PrintCondition();
+
   } else {
     if (TestParam2 != 0L)
       cout << "    " << TestParam1->GetName() << " " << conditional << " " << TestParam2->GetName();
index c778e0f79ae5bf71e0fbec0799d3fefcbf36ffe9..cc63d117a4333c039e29a7b7d420cd42bf4835f2 100644 (file)
@@ -89,7 +89,7 @@ private:
 
   static string indent;
 
-  vector <FGCondition> conditions;
+  vector <FGCondition*> conditions;
   void InitializeConditionals(void);
 
   void Debug(int from);
index f040e2a65f59711a4daa52bb205b51f5b2fb7c2e..7a01df058f917d849a53e826fc6f68aee5ea0b46 100755 (executable)
@@ -53,40 +53,85 @@ FGFunction::FGFunction(FGPropertyManager* propMan, Element* el, string prefix)
   cached = false;
   cachedValue = -HUGE_VAL;
 
+  property_string = "property";
+  value_string = "value";
+  table_string = "table";
+  p_string = "p";
+  v_string = "v";
+  t_string = "t";
+
+  function_string = "function";
+  description_string = "description";
+  sum_string = "sum";
+  difference_string = "difference";
+  product_string = "product";
+  quotient_string = "quotient";
+  pow_string = "pow";
+  exp_string = "exp";
+  abs_string = "abs";
+  sin_string = "sin";
+  cos_string = "cos";
+  tan_string = "tan";
+  asin_string = "asin";
+  acos_string = "acos";
+  atan_string = "atan";
+  atan2_string = "atan2";
+  min_string = "min";
+  max_string = "max";
+  avg_string = "avg";
+  fraction_string = "fraction";
+  mod_string = "mod";
+  random_string = "random";
+  integer_string = "integer";
+
   Name = el->GetAttributeValue("name");
   operation = el->GetName();
 
-  if (operation == string("function")) {
+  if (operation == function_string) {
     Type = eTopLevel;
-  } else if (operation == string("product")) {
+  } else if (operation == product_string) {
     Type = eProduct;
-  } else if (operation == string("difference")) {
+  } else if (operation == difference_string) {
     Type = eDifference;
-  } else if (operation == string("sum")) {
+  } else if (operation == sum_string) {
     Type = eSum;
-  } else if (operation == string("quotient")) {
+  } else if (operation == quotient_string) {
     Type = eQuotient;
-  } else if (operation == string("pow")) {
+  } else if (operation == pow_string) {
     Type = ePow;
-  } else if (operation == string("abs")) {
+  } else if (operation == abs_string) {
     Type = eAbs;
-  } else if (operation == string("sin")) {
+  } else if (operation == sin_string) {
     Type = eSin;
-  } else if (operation == string("exp")) {
+  } else if (operation == exp_string) {
     Type = eExp;
-  } else if (operation == string("cos")) {
+  } else if (operation == cos_string) {
     Type = eCos;
-  } else if (operation == string("tan")) {
+  } else if (operation == tan_string) {
     Type = eTan;
-  } else if (operation == string("asin")) {
+  } else if (operation == asin_string) {
     Type = eASin;
-  } else if (operation == string("acos")) {
+  } else if (operation == acos_string) {
     Type = eACos;
-  } else if (operation == string("atan")) {
+  } else if (operation == atan_string) {
     Type = eATan;
-  } else if (operation == string("atan2")) {
+  } else if (operation == atan2_string) {
     Type = eATan2;
-  } else if (operation != string("description")) {
+  } else if (operation == min_string) {
+    Type = eMin;
+  } else if (operation == max_string) {
+    Type = eMax;
+  } else if (operation == avg_string) {
+    Type = eAvg;
+  } else if (operation == fraction_string) {
+    Type = eFrac;
+  } else if (operation == integer_string) {
+    Type = eInteger;
+  } else if (operation == mod_string) {
+    Type = eMod;
+  } else if (operation == random_string) {
+    Type = eRandom;
+  } else if (operation != description_string) {
     cerr << "Bad operation " << operation << " detected in configuration file" << endl;
   }
 
@@ -105,7 +150,7 @@ FGFunction::FGFunction(FGPropertyManager* propMan, Element* el, string prefix)
     operation = element->GetName();
 
     // data types
-    if (operation == string("property")) {
+    if (operation == property_string || operation == p_string) {
       property_name = element->GetDataLine();
       FGPropertyManager* newNode = PropertyManager->GetNode(property_name);
       if (newNode == 0) {
@@ -114,28 +159,35 @@ FGFunction::FGFunction(FGPropertyManager* propMan, Element* el, string prefix)
       } else {
         Parameters.push_back(new FGPropertyValue( newNode ));
       }
-    } else if (operation == string("value")) {
+    } else if (operation == value_string || operation == v_string) {
       Parameters.push_back(new FGRealValue(element->GetDataAsNumber()));
-    } else if (operation == string("table")) {
+    } else if (operation == table_string || operation == t_string) {
       Parameters.push_back(new FGTable(PropertyManager, element));
     // operations
-    } else if (operation == string("product") ||
-               operation == string("difference") ||
-               operation == string("sum") ||
-               operation == string("quotient") ||
-               operation == string("pow") ||
-               operation == string("exp") ||
-               operation == string("abs") ||
-               operation == string("sin") ||
-               operation == string("cos") ||
-               operation == string("tan") ||
-               operation == string("asin") ||
-               operation == string("acos") ||
-               operation == string("atan") ||
-               operation == string("atan2"))
+    } else if (operation == product_string ||
+               operation == difference_string ||
+               operation == sum_string ||
+               operation == quotient_string ||
+               operation == pow_string ||
+               operation == exp_string ||
+               operation == abs_string ||
+               operation == sin_string ||
+               operation == cos_string ||
+               operation == tan_string ||
+               operation == asin_string ||
+               operation == acos_string ||
+               operation == atan_string ||
+               operation == atan2_string ||
+               operation == min_string ||
+               operation == max_string ||
+               operation == fraction_string ||
+               operation == integer_string ||
+               operation == mod_string ||
+               operation == random_string ||
+               operation == avg_string )
     {
       Parameters.push_back(new FGFunction(PropertyManager, element));
-    } else if (operation != string("description")) {
+    } else if (operation != description_string) {
       cerr << "Bad operation " << operation << " detected in configuration file" << endl;
     }
     element = el->GetNextElement();
@@ -150,14 +202,7 @@ FGFunction::FGFunction(FGPropertyManager* propMan, Element* el, string prefix)
 
 FGFunction::~FGFunction(void)
 {
-  if (!Name.empty()) {
-    string tmp = PropertyManager->mkPropertyName(Prefix + Name, false); // Allow upper case
-    PropertyManager->Untie(tmp);
-  }
-
-  for (unsigned int i=0; i<Parameters.size(); i++) {
-    delete Parameters[i];
-  }
+  for (unsigned int i=0; i<Parameters.size(); i++) delete Parameters[i];
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -177,6 +222,7 @@ void FGFunction::cacheValue(bool cache)
 double FGFunction::GetValue(void) const
 {
   unsigned int i;
+  double scratch;
 
   if (cached) return cachedValue;
 
@@ -233,6 +279,35 @@ double FGFunction::GetValue(void) const
   case eATan2:
     temp = atan2(temp, Parameters[1]->GetValue());
     break;
+  case eMod:
+    temp = ((int)temp) % ((int) Parameters[1]->GetValue());
+    break;
+  case eMin:
+    for (i=1;i<Parameters.size();i++) {
+      if (Parameters[i]->GetValue() < temp) temp = Parameters[i]->GetValue();
+    }    
+    break;
+  case eMax:
+    for (i=1;i<Parameters.size();i++) {
+      if (Parameters[i]->GetValue() > temp) temp = Parameters[i]->GetValue();
+    }    
+    break;
+  case eAvg:
+    for (i=1;i<Parameters.size();i++) {
+      temp += Parameters[i]->GetValue();
+    }
+    temp /= Parameters.size();
+    break;
+  case eFrac:
+    temp = modf(temp, &scratch);
+    break;
+  case eInteger:
+    modf(temp, &scratch);
+    temp = scratch;
+    break;
+  case eRandom:
+    temp = GaussianRandomNumber();
+    break;
   default:
     cerr << "Unknown function operation type" << endl;
     break;
@@ -255,6 +330,33 @@ string FGFunction::GetValueAsString(void) const
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+double FGFunction::GaussianRandomNumber(void) const
+{
+  static double V1, V2, S;
+  static int phase = 0;
+  double X;
+
+  if (phase == 0) {
+    do {
+      double U1 = (double)rand() / RAND_MAX;
+      double U2 = (double)rand() / RAND_MAX;
+
+      V1 = 2 * U1 - 1;
+      V2 = 2 * U2 - 1;
+      S = V1 * V1 + V2 * V2;
+    } while(S >= 1 || S == 0);
+
+      X = V1 * sqrt(-2 * log(S) / S);
+  } else
+    X = V2 * sqrt(-2 * log(S) / S);
+
+  phase = 1 - phase;
+
+  return X;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 void FGFunction::bind(void)
 {
   if ( !Name.empty() ) {
index 47bc1ccc38f4d236e780785eb490567e5da9113b..435b031b6fb8206d982089296d618dd353707f58 100755 (executable)
@@ -77,6 +77,13 @@ A function definition consists of an operation, a value, a table, or a property
 - acos (takes 1 arg)
 - atan (takes 1 arg)
 - atan2 (takes 2 args)
+- min (takes n args)
+- max (takes n args)
+- avg (takes n args)
+- fraction
+- mod
+- random (Gaussian random number)
+- integer
 
 An operation is defined in the configuration file as in the following example:
 
@@ -137,6 +144,8 @@ functions require (except atan2, which takes two arguments).
 DECLARATION: FGFunction
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
+// Todo: Does this class need a copy constructor, like FGLGear?
+
 class FGFunction : public FGParameter
 {
 public:
@@ -184,10 +193,41 @@ private:
   FGPropertyManager* const PropertyManager;
   bool cached;
   string Prefix;
+  string description_string;
+  string property_string;
+  string value_string;
+  string table_string;
+  string p_string;
+  string v_string;
+  string t_string;
+  string function_string;
+  string sum_string;
+  string difference_string;
+  string product_string;
+  string quotient_string;
+  string pow_string;
+  string exp_string;
+  string abs_string;
+  string sin_string;
+  string cos_string;
+  string tan_string;
+  string asin_string;
+  string acos_string;
+  string atan_string;
+  string atan2_string;
+  string min_string;
+  string max_string;
+  string avg_string;
+  string fraction_string;
+  string mod_string;
+  string random_string;
+  string integer_string;
   double cachedValue;
   enum functionType {eTopLevel=0, eProduct, eDifference, eSum, eQuotient, ePow,
-                     eExp, eAbs, eSin, eCos, eTan, eASin, eACos, eATan, eATan2} Type;
+                     eExp, eAbs, eSin, eCos, eTan, eASin, eACos, eATan, eATan2,
+                     eMin, eMax, eAvg, eFrac, eInteger, eMod, eRandom} Type;
   string Name;
+  double GaussianRandomNumber(void) const;
   void bind(void);
   void Debug(int from);
 };
index f9a9b52b3a5d7212abafdaf4b340cd0e52eba9e4..6ba2328df0cef40efc891aeb9ba93739a5c0883f 100644 (file)
@@ -65,6 +65,22 @@ static const char *IdHdr = ID_LOCATION;
 CLASS IMPLEMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
+FGLocation::FGLocation(void)
+{
+  mCacheValid = false;
+  initial_longitude = 0.0;
+  a = 0.0;
+  b = 0.0;
+  a2 = 0.0;
+  b2 = 0.0;
+  e2 = 1.0;
+  e = 1.0;
+  eps2 = -1.0;
+  f = 1.0;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 FGLocation::FGLocation(double lon, double lat, double radius)
 {
   mCacheValid = false;
@@ -73,6 +89,15 @@ FGLocation::FGLocation(double lon, double lat, double radius)
   double cosLat = cos(lat);
   double sinLon = sin(lon);
   double cosLon = cos(lon);
+  initial_longitude = lon;
+  a = 0.0;
+  b = 0.0;
+  a2 = 0.0;
+  b2 = 0.0;
+  e2 = 1.0;
+  e = 1.0;
+  eps2 = -1.0;
+  f = 1.0;
   mECLoc = FGColumnVector3( radius*cosLat*cosLon,
                             radius*cosLat*sinLon,
                             radius*sinLat );
@@ -94,6 +119,8 @@ void FGLocation::SetLongitude(double longitude)
 
   mCacheValid = false;
 
+  // Need to figure out how to set the initial_longitude here
+
   mECLoc(eX) = rtmp*cos(longitude);
   mECLoc(eY) = rtmp*sin(longitude);
 }
@@ -137,12 +164,69 @@ void FGLocation::SetRadius(double radius)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGLocation::SetPosition(double lon, double lat, double radius)
+{
+  mCacheValid = false;
+
+  double sinLat = sin(lat);
+  double cosLat = cos(lat);
+  double sinLon = sin(lon);
+  double cosLon = cos(lon);
+  initial_longitude = lon;
+  mECLoc = FGColumnVector3( radius*cosLat*cosLon,
+                            radius*cosLat*sinLon,
+                            radius*sinLat );
+  ComputeDerived();
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGLocation::SetEllipse(double semimajor, double semiminor)
+{
+  mCacheValid = false;
+
+  a = semimajor;
+  b = semiminor;
+  a2 = a*a;
+  b2 = b*b;
+  e2 = 1.0 - b2/a2;
+  e = sqrt(e2);
+  eps2 = a2/b2 - 1.0;
+  f = 1.0 - b/a;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+// Compute the ECEF to ECI transformation matrix using Stevens and Lewis "Aircraft
+// Control and Simulation", second edition, eqn. 1.4-12, pg. 39
+
+const FGMatrix33& FGLocation::GetTec2i(double epa)
+{
+  double mu = epa - initial_longitude;
+  mTec2i = FGMatrix33( cos(mu), -sin(mu), 0.0,
+                       sin(mu),  cos(mu), 0.0,
+                            0.0,     0.0, 1.0 );
+  return mTec2i;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+const FGMatrix33& FGLocation::GetTi2ec(double epa)
+{
+  double mu = epa - initial_longitude;
+  mTi2ec = FGMatrix33( cos(mu), sin(mu), 0.0,
+                      -sin(mu), cos(mu), 0.0,
+                           0.0,      0.0, 1.0 );
+  return mTi2ec;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 void FGLocation::ComputeDerivedUnconditional(void) const
 {
   // The radius is just the Euclidean norm of the vector.
   mRadius = mECLoc.Magnitude();
 
-  // The distance of the location to the y-axis, which is the axis
+  // The distance of the location to the Z-axis, which is the axis
   // through the poles.
   double rxy = sqrt(mECLoc(eX)*mECLoc(eX) + mECLoc(eY)*mECLoc(eY));
 
@@ -178,12 +262,47 @@ void FGLocation::ComputeDerivedUnconditional(void) const
     mLat = atan2( mECLoc(eZ), rxy );
 
   // Compute the transform matrices from and to the earth centered frame.
-  // see Durham Chapter 4, problem 1, page 52
+  // See Stevens and Lewis, "Aircraft Control and Simulation", Second Edition,
+  // Eqn. 1.4-13, page 40. 
   mTec2l = FGMatrix33( -cosLon*sinLat, -sinLon*sinLat,  cosLat,
                            -sinLon   ,     cosLon    ,    0.0 ,
                        -cosLon*cosLat, -sinLon*cosLat, -sinLat  );
 
   mTl2ec = mTec2l.Transposed();
+  
+  // Calculate the geodetic latitude base on AIAA Journal of Guidance and Control paper,
+  // "Improved Method for Calculating Exact Geodetic Latitude and Altitude", and
+  // "Improved Method for Calculating Exact Geodetic Latitude and Altitude, Revisited",
+  // author: I. Sofair
+
+  if (a != 0.0 && b != 0.0) {
+    double c, p, q, s, t, u, v, w, z, p2, u2, r02, r0;
+    double Ne, P, Q0, Q, signz0, sqrt_q; 
+    p  = fabs(mECLoc(eZ))/eps2;
+    r02 = mECLoc(eX)*mECLoc(eX) + mECLoc(eY)*mECLoc(eY);
+    s  = r02/(e2*eps2);
+    p2 = p*p;
+    q  = p2 - b2 + s;
+    sqrt_q = sqrt(q);
+    if (q>0)
+    {
+      u  = p/sqrt_q;
+      u2 = p2/q;
+      v  = b2*u2/q;
+      P  = 27.0*v*s/q;
+      Q0 = sqrt(P+1) + sqrt(P);
+      Q  = pow(Q0, 0.66666666667);
+      t  = (1.0 + Q + 1.0/Q)/6.0;
+      c  = sqrt(u2 - 1 + 2.0*t);
+      w  = (c - u)/2.0;
+      signz0 = mECLoc(eZ)>=0?1.0:-1.0;
+      z  = signz0*sqrt_q*(w+sqrt(sqrt(t*t+v)-u*w-0.5*t-0.25));
+      Ne = a*sqrt(1+eps2*z*z/b2);
+      mGeodLat = asin((eps2+1.0)*(z/Ne));
+      r0 = sqrt(r02);
+      GeodeticAltitude = r0*cos(mGeodLat) + mECLoc(eZ)*sin(mGeodLat) - a2/Ne;
+    }
+  }
 
   // Mark the cached values as valid
   mCacheValid = true;
@@ -191,31 +310,4 @@ void FGLocation::ComputeDerivedUnconditional(void) const
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGLocation::bind(FGPropertyManager* PropertyManager, const string& prefix) const
-{
-  PropertyManager->Tie(prefix + "lat-gc-rad", (FGLocation*)this,
-                       &FGLocation::GetLatitude);
-  PropertyManager->Tie(prefix + "lat-gc-deg", (FGLocation*)this,
-                       &FGLocation::GetLatitudeDeg);
-  PropertyManager->Tie(prefix + "long-gc-rad", (FGLocation*)this,
-                       &FGLocation::GetLongitude);
-  PropertyManager->Tie(prefix + "long-gc-deg", (FGLocation*)this,
-                       &FGLocation::GetLongitudeDeg);
-  PropertyManager->Tie(prefix + "radius-ft", (FGLocation*)this,
-                       &FGLocation::GetRadius);
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGLocation::unbind(FGPropertyManager* PropertyManager, const string& prefix) const
-{
-  PropertyManager->Untie(prefix + "lat-gc-rad");
-  PropertyManager->Untie(prefix + "lat-gc-deg");
-  PropertyManager->Untie(prefix + "long-gc-rad");
-  PropertyManager->Untie(prefix + "long-gc-deg");
-  PropertyManager->Untie(prefix + "radius-ft");
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
 } // namespace JSBSim
index 5f9553059ac0ad1a5a9aeabc19b6715bfde8131d..ddfbc5071a2a6c2b117e01fb93c7df321a582141 100644 (file)
@@ -128,6 +128,7 @@ CLASS DOCUMENTATION
     converts latitude to a geodetic value and uses that. In order to get best
     matching relative to a map, geocentric latitude must be converted to geodetic.
 
+    @see Stevens and Lewis, "Aircraft Control and Simulation", Second edition
     @see W. C. Durham "Aircraft Dynamics & Control", section 2.2
 
     @author Mathias Froehlich
@@ -142,24 +143,33 @@ class FGLocation : virtual FGJSBBase
 {
 public:
   /** Default constructor. */
-  FGLocation() { mCacheValid = false; }
+  FGLocation(void);
 
   /** Constructor to set the longitude, latitude and the distance
       from the center of the earth.
       @param lon longitude
       @param lat GEOCENTRIC latitude
-      @param distance from center of earth to vehicle in feet*/
+      @param radius distance from center of earth to vehicle in feet*/
   FGLocation(double lon, double lat, double radius);
 
-  /** Copy constructor. */
-  FGLocation(const FGColumnVector3& lv)
-    : mECLoc(lv), mCacheValid(false) {}
+  /** Column constructor. */
+  FGLocation(const FGColumnVector3& lv) : mECLoc(lv), mCacheValid(false)
+  {
+    a = 0.0;
+    b = 0.0;
+    a2 = 0.0;
+    b2 = 0.0;
+    e2 = 1.0;
+    e = 1.0;
+    eps2 = -1.0;
+    f = 1.0;
+  }
 
   /** Copy constructor. */
   FGLocation(const FGLocation& l)
-    : mECLoc(l.mECLoc), mCacheValid(l.mCacheValid) {
-    if (!mCacheValid)
-      return;
+    : mECLoc(l.mECLoc), mCacheValid(l.mCacheValid)
+  {
+//    if (!mCacheValid) return; // This doesn't seem right.
 
     mLon = l.mLon;
     mLat = l.mLat;
@@ -167,8 +177,67 @@ public:
 
     mTl2ec = l.mTl2ec;
     mTec2l = l.mTec2l;
+
+    a = l.a;
+    b = l.b;
+    a2 = l.a2;
+    b2 = l.b2;
+    e2 = l.e2;
+    e = l.e;
+    eps2 = l.eps2;
+    f = l.f;
+
+    initial_longitude = l.initial_longitude;
   }
 
+  /** Set the longitude.
+      @param longitude Longitude in rad to set.
+      Sets the longitude of the location represented with this class
+      instance to the value of the given argument. The value is meant
+      to be in rad. The latitude and the radius value are preserved
+      with this call with the exception of radius being equal to
+      zero. If the radius is previously set to zero it is changed to be
+      equal to 1.0 past this call. Longitude is positive east and negative west. */
+  void SetLongitude(double longitude);
+
+  /** Set the latitude.
+      @param latitude Latitude in rad to set.
+      Sets the latitude of the location represented with this class
+      instance to the value of the given argument. The value is meant
+      to be in rad. The longitude and the radius value are preserved
+      with this call with the exception of radius being equal to
+      zero. If the radius is previously set to zero it is changed to be
+      equal to 1.0 past this call.
+      Latitude is positive north and negative south.
+      The arguments should be within the bounds of -pi/2 <= lat <= pi/2.
+      The behavior of this function with arguments outside this range is
+      left as an exercise to the gentle reader ... */
+  void SetLatitude(double latitude);
+
+  /** Set the distance from the center of the earth.
+      @param radius Radius in ft to set.
+      Sets the radius of the location represented with this class
+      instance to the value of the given argument. The value is meant
+      to be in ft. The latitude and longitude values are preserved
+      with this call with the exception of radius being equal to
+      zero. If the radius is previously set to zero, latitude and
+      longitude is set equal to zero past this call.
+      The argument should be positive.
+      The behavior of this function called with a negative argument is
+      left as an exercise to the gentle reader ... */
+  void SetRadius(double radius);
+
+  /** Sets the longitude, latitude and the distance from the center of the earth.
+      @param lon longitude in radians
+      @param lat GEOCENTRIC latitude in radians
+      @param radius distance from center of earth to vehicle in feet*/
+  void SetPosition(double lon, double lat, double radius);
+
+  /** Sets the semimajor and semiminor axis lengths for this planet.
+      The eccentricity and flattening are calculated from the semimajor
+      and semiminor axis lengths */
+  void SetEllipse(double semimajor, double semiminor);
+
   /** Get the longitude.
       @return the longitude in rad of the location represented with this
       class instance. The returned values are in the range between
@@ -181,16 +250,6 @@ public:
       -180 <= lon <= 180.  Longitude is positive east and negative west. */
   double GetLongitudeDeg() const { ComputeDerived(); return radtodeg*mLon; }
 
-  /** Set the longitude.
-      @param longitude Longitude in rad to set.
-      Sets the longitude of the location represented with this class
-      instance to the value of the given argument. The value is meant
-      to be in rad. The latitude and the radius value are preserved
-      with this call with the exception of radius being equal to
-      zero. If the radius is previously set to zero it is changed to be
-      equal to 1.0 past this call. Longitude is positive east and negative west. */
-  void SetLongitude(double longitude);
-
   /** Get the sine of Longitude. */
   double GetSinLongitude() const { ComputeDerived(); return -mTec2l(2,1); }
 
@@ -203,25 +262,26 @@ public:
       -pi/2 <= lon <= pi/2. Latitude is positive north and negative south. */
   double GetLatitude() const { ComputeDerived(); return mLat; }
 
+  /** Get the geodetic latitude.
+      @return the geodetic latitude in rad of the location represented with this
+      class instance. The returned values are in the range between
+      -pi/2 <= lon <= pi/2. Latitude is positive north and negative south. */
+  double GetGeodLatitudeRad(void) const { ComputeDerived(); return mGeodLat; }
+
   /** Get the latitude.
       @return the latitude in deg of the location represented with this
-      class instance. The returned values are in the range between
+      class instance. The returned value is in the range between
       -90 <= lon <= 90. Latitude is positive north and negative south. */
   double GetLatitudeDeg() const { ComputeDerived(); return radtodeg*mLat; }
 
-  /** Set the latitude.
-      @param latitude Latitude in rad to set.
-      Sets the latitude of the location represented with this class
-      instance to the value of the given argument. The value is meant
-      to be in rad. The longitude and the radius value are preserved
-      with this call with the exception of radius being equal to
-      zero. If the radius is previously set to zero it is changed to be
-      equal to 1.0 past this call.
-      Latitude is positive north and negative south.
-      The arguments should be within the bounds of -pi/2 <= lat <= pi/2.
-      The behavior of this function with arguments outside this range is
-      left as an exercise to the gentle reader ... */
-  void SetLatitude(double latitude);
+  /** Get the geodetic latitude in degrees.
+      @return the geodetic latitude in degrees of the location represented by
+      this class instance. The returned value is in the range between
+      -90 <= lon <= 90. Latitude is positive north and negative south. */
+  double GetGeodLatitudeDeg(void) const { ComputeDerived(); return radtodeg*mGeodLat; }
+
+  /** Gets the geodetic altitude in feet. */
+  double GetGeodAltitude(void) const { return GeodeticAltitude;}
 
   /** Get the sine of Latitude. */
   double GetSinLatitude() const { ComputeDerived(); return -mTec2l(3,3); }
@@ -245,19 +305,6 @@ public:
       always positive. */
   double GetRadius() const { ComputeDerived(); return mRadius; }
 
-  /** Set the distance from the center of the earth.
-      @param radius Radius in ft to set.
-      Sets the radius of the location represented with this class
-      instance to the value of the given argument. The value is meant
-      to be in ft. The latitude and longitude values are preserved
-      with this call with the exception of radius being equal to
-      zero. If the radius is previously set to zero, latitude and
-      longitude is set equal to zero past this call.
-      The argument should be positive.
-      The behavior of this function called with a negative argument is
-      left as an exercise to the gentle reader ... */
-  void SetRadius(double radius);
-
   /** Transform matrix from local horizontal to earth centered frame.
       Returns a const reference to the rotation matrix of the transform from
       the local horizontal frame to the earth centered frame. */
@@ -268,9 +315,19 @@ public:
       the earth centered frame to the local horizontal frame. */
   const FGMatrix33& GetTec2l(void) const { ComputeDerived(); return mTec2l; }
 
+  /** Transform matrix from inertial to earth centered frame.
+      Returns a const reference to the rotation matrix of the transform from
+      the inertial frame to the earth centered frame (ECI to ECEF). */
+  const FGMatrix33& GetTi2ec(double epa);
+
+  /** Transform matrix from the earth centered to inertial frame.
+      Returns a const reference to the rotation matrix of the transform from
+      the earth centered frame to the inertial frame (ECEF to ECI). */
+  const FGMatrix33& GetTec2i(double epa);
+
   /** Conversion from Local frame coordinates to a location in the
       earth centered and fixed frame.
-      @parm lvec Vector in the local horizontal coordinate frame
+      @param lvec Vector in the local horizontal coordinate frame
       @return The location in the earth centered and fixed frame */
   FGLocation LocalToLocation(const FGColumnVector3& lvec) const {
     ComputeDerived(); return mTl2ec*lvec + mECLoc;
@@ -278,7 +335,7 @@ public:
 
   /** Conversion from a location in the earth centered and fixed frame
       to local horizontal frame coordinates.
-      @parm ecvec Vector in the earth centered and fixed frame
+      @param ecvec Vector in the earth centered and fixed frame
       @return The vector in the local horizontal coordinate frame */
   FGColumnVector3 LocationToLocal(const FGColumnVector3& ecvec) const {
     ComputeDerived(); return mTec2l*(ecvec - mECLoc);
@@ -304,8 +361,8 @@ public:
       @param idx the component index.
       @return the value of the matrix entry at the given index.
       Indices are counted starting with 1.
-      This function is just a shortcut for the @ref double
-      operator()(unsigned int idx) const function. It is
+      This function is just a shortcut for the <tt>double
+      operator()(unsigned int idx) const</tt> function. It is
       used internally to access the elements in a more convenient way.
       Note that the index given in the argument is unchecked. */
   double Entry(unsigned int idx) const { return mECLoc.Entry(idx); }
@@ -322,11 +379,22 @@ public:
     mCacheValid = false; return mECLoc.Entry(idx);
   }
 
-  const FGLocation& operator=(const FGLocation& l) {
+  const FGLocation& operator=(const FGColumnVector3& v)
+  {
+    mECLoc(eX) = v(eX);
+    mECLoc(eY) = v(eY);
+    mECLoc(eZ) = v(eZ);
+    mCacheValid = false;
+    ComputeDerived();
+    return *this;
+  }
+
+  const FGLocation& operator=(const FGLocation& l)
+  {
     mECLoc = l.mECLoc;
     mCacheValid = l.mCacheValid;
-    if (!mCacheValid)
-      return *this;
+
+//    if (!mCacheValid) return *this; // Why is this here for an assignment operator?
 
     mLon = l.mLon;
     mLat = l.mLat;
@@ -335,6 +403,17 @@ public:
     mTl2ec = l.mTl2ec;
     mTec2l = l.mTec2l;
 
+    a = l.a;
+    b = l.b;
+    a2 = l.a2;
+    b2 = l.b2;
+    e2 = l.e2;
+    e = l.e;
+    eps2 = l.eps2;
+    f = l.f;
+
+    initial_longitude = l.initial_longitude;
+
     return *this;
   }
   bool operator==(const FGLocation& l) const {
@@ -375,14 +454,6 @@ public:
     return mECLoc;
   }
 
-  /** Ties into the property tree.
-      Ties the variables represented by this class into the property tree. */
-  void bind(FGPropertyManager*, const string&) const;
-
-  /** Remove from property tree.
-      Unties the variables represented by this class into the property tree. */
-  void unbind(FGPropertyManager*, const string&) const;
-
 private:
   /** Computation of derived values.
       This function re-computes the derived values like lat/lon and
@@ -413,10 +484,26 @@ private:
   mutable double mLon;
   mutable double mLat;
   mutable double mRadius;
+  mutable double mGeodLat;
+  mutable double GeodeticAltitude;
+  
+  double initial_longitude;
 
   /** The cached rotation matrices from and to the associated frames. */
   mutable FGMatrix33 mTl2ec;
   mutable FGMatrix33 mTec2l;
+  mutable FGMatrix33 mTi2ec;
+  mutable FGMatrix33 mTec2i;
+  
+  /* Terms for geodetic latitude calculation. Values are from WGS84 model */
+  double a;    // Earth semimajor axis in feet (6,378,137.0 meters)
+  double b;    // Earth semiminor axis in feet (6,356,752.3142 meters)
+  double a2;
+  double b2;
+  double e;    // Earth eccentricity
+  double e2;   // Earth eccentricity squared
+  double eps2; //
+  double f;    // Flattening
 
   /** A data validity flag.
       This class implements caching of the derived values like the
index 60b1ff885dd5702abcc5bc09ed9445874181b98a..1204612c1b33f2c9641e312d2f592c654426c52f 100644 (file)
@@ -216,8 +216,8 @@ public:
   }
 
   /** Read access the entries of the matrix.
-      This function is just a shortcut for the @ref double&
-      operator()(unsigned int row, unsigned int col) function. It is
+      This function is just a shortcut for the <tt>double&
+      operator()(unsigned int row, unsigned int col)</tt> function. It is
       used internally to access the elements in a more convenient way.
 
       Note that the indices given in the arguments are unchecked.
@@ -233,8 +233,8 @@ public:
   }
 
   /** Write access the entries of the matrix.
-      This function is just a shortcut for the @ref double&
-      operator()(unsigned int row, unsigned int col) function. It is
+      This function is just a shortcut for the <tt>double&
+      operator()(unsigned int row, unsigned int col)</tt> function. It is
       used internally to access the elements in a more convenient way.
 
       Note that the indices given in the arguments are unchecked.
index 38e7e76e986c8d89283058ae2c238aa3103befaa..700d7a3c56032f5663a595f336994b0fcd864f67 100644 (file)
@@ -125,9 +125,10 @@ FGQuaternion::FGQuaternion(double phi, double tht, double psi)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-/**
-   Returns the derivative of the quaternion coresponding to the
-   angular velocities PQR.
+/** Returns the derivative of the quaternion corresponding to the
+    angular velocities PQR.
+    See Stevens and Lewis, "Aircraft Control and Simulation", Second Edition,
+    Equation 1.3-36. 
 */
 FGQuaternion FGQuaternion::GetQDot(const FGColumnVector3& PQR) const {
   double norm = Magnitude();
index 832f109184575b5c7e52f267fd5530a0376651bb..a17008fd6032e995e9513a97dd6ecc4b1a5f4118 100644 (file)
@@ -146,11 +146,13 @@ public:
   /// Destructor.
   ~FGQuaternion() {}
 
-  /** Quaternion 'velocity' for given angular rates.
+  /** Quaternion derivative for given angular rates.
       Computes the quaternion derivative which results from the given
       angular velocities
       @param PQR a constant reference to the body rate vector
-      @return the quaternion derivative */
+      @return the quaternion derivative
+      @see Stevens and Lewis, "Aircraft Control and Simulation", Second Edition,
+           Equation 1.3-36. */
   FGQuaternion GetQDot(const FGColumnVector3& PQR) const;
 
   /** Transformation matrix.
@@ -166,7 +168,7 @@ public:
   /** Retrieves the Euler angles.
       @return a reference to the triad of euler angles corresponding
       to this quaternion rotation.
-      @units radians  */
+      units radians  */
   const FGColumnVector3& GetEuler(void) const {
     ComputeDerived();
     return mEulerAngles;
@@ -174,9 +176,10 @@ public:
 
   /** Retrieves the Euler angles.
       @param i the euler angle index.
+      units radians.
       @return a reference to the i-th euler angles corresponding
       to this quaternion rotation.
-      @units radians */
+   */
   double GetEuler(int i) const {
     ComputeDerived();
     return mEulerAngles(i);
@@ -186,7 +189,7 @@ public:
       @param i the euler angle index.
       @return a reference to the i-th euler angles corresponding
       to this quaternion rotation.
-      @units degrees */
+      units degrees */
   double GetEulerDeg(int i) const {
     ComputeDerived();
     return radtodeg*mEulerAngles(i);
@@ -237,8 +240,8 @@ public:
       Return the value of the matrix entry at the given index.
       Indices are counted starting with 1.
 
-      This function is just a shortcut for the @ref double
-      operator()(unsigned int idx) const function. It is
+      This function is just a shortcut for the <tt>double
+      operator()(unsigned int idx) const</tt> function. It is
       used internally to access the elements in a more convenient way.
 
       Note that the index given in the argument is unchecked.
@@ -252,8 +255,8 @@ public:
       Return a reference to the vector entry at the given index.
       Indices are counted starting with 1.
 
-      This function is just a shortcut for the @ref double&
-      operator()(unsigned int idx) function. It is
+      This function is just a shortcut for the <tt>double&
+      operator()(unsigned int idx)</tt> function. It is
       used internally to access the elements in a more convenient way.
 
       Note that the index given in the argument is unchecked.
@@ -481,7 +484,7 @@ private:
 /** Scalar multiplication.
 
     @param scalar scalar value to multiply with.
-    @param p Vector to multiply.
+    @param q Vector to multiply.
 
     Multiply the Vector with a scalar value.
 */
index 100d5d784d1e9f5d0cd07075ef52cdd1e073ddfe..ed45983c6a2d1a54d4f474c2b7bba7d5342627cc 100644 (file)
@@ -300,11 +300,6 @@ double** FGTable::Allocate(void)
 
 FGTable::~FGTable()
 {
-  if (!Name.empty() && !internal) {
-    string tmp = PropertyManager->mkPropertyName(Name, false); // Allow upper case
-    PropertyManager->Untie(tmp);
-  }
-
   if (nTables > 0) {
     for (unsigned int i=0; i<nTables; i++) delete Tables[i];
     Tables.clear();
index 9d7d31dcbc5c6bb590c8e55a2a416e8bf5963e80..e946a5b479defc2fb9315aacc1387fec30eca466 100644 (file)
@@ -39,7 +39,7 @@ INCLUDES
 #include "FGAerodynamics.h"
 #include "FGPropagate.h"
 #include "FGAircraft.h"
-#include "FGState.h"
+#include "FGAuxiliary.h"
 #include "FGMassBalance.h"
 #include <input_output/FGPropertyManager.h>
 
@@ -48,10 +48,6 @@ namespace JSBSim {
 static const char *IdSrc = "$Id$";
 static const char *IdHdr = ID_AERODYNAMICS;
 
-const unsigned NAxes=6;
-const char* AxisNames[] = { "drag", "side-force", "lift", "rolling-moment",
-                            "pitching-moment","yawing-moment" };
-
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 CLASS IMPLEMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
@@ -61,12 +57,21 @@ FGAerodynamics::FGAerodynamics(FGFDMExec* FDMExec) : FGModel(FDMExec)
 {
   Name = "FGAerodynamics";
 
-  AxisIdx["DRAG"]  = 0;
-  AxisIdx["SIDE"]  = 1;
-  AxisIdx["LIFT"]  = 2;
-  AxisIdx["ROLL"]  = 3;
-  AxisIdx["PITCH"] = 4;
-  AxisIdx["YAW"]   = 5;
+  AxisIdx["DRAG"]   = 0;
+  AxisIdx["SIDE"]   = 1;
+  AxisIdx["LIFT"]   = 2;
+  AxisIdx["ROLL"]   = 3;
+  AxisIdx["PITCH"]  = 4;
+  AxisIdx["YAW"]    = 5;
+
+  AxisIdx["AXIAL"]  = 0;
+  AxisIdx["NORMAL"] = 2;
+
+  AxisIdx["X"] = 0;
+  AxisIdx["Y"] = 1;
+  AxisIdx["Z"] = 2;
+
+  axisType = atNone;
 
   Coeff = new CoeffArray[6];
 
@@ -99,15 +104,30 @@ FGAerodynamics::~FGAerodynamics()
   for (i=0; i<variables.size(); i++)
     delete variables[i];
 
-  if (AeroRPShift) delete AeroRPShift;
-
-  unbind();
+  delete AeroRPShift;
 
   Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGAerodynamics::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  impending_stall = stall_hyst = 0.0;
+  alphaclmin = alphaclmax = 0.0;
+  alphahystmin = alphahystmax = 0.0;
+  clsq = lod = 0.0;
+  alphaw = 0.0;
+  bi2vel = ci2vel = 0.0;
+  AeroRPShift = 0;
+  vDeltaRP.InitMatrix();
+
+  return true;
+}
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGAerodynamics::Run(void)
 {
   unsigned int axis_ctr, ctr, i;
@@ -143,42 +163,58 @@ bool FGAerodynamics::Run(void)
     }
   }
 
-  vLastFs = vFs;
-  vFs.InitMatrix();
+  vFw.InitMatrix();
+  vFnative.InitMatrix();
 
   // Tell the variable functions to cache their values, so while the aerodynamic
   // functions are being calculated for each axis, these functions do not get
   // calculated each time, but instead use the values that have already
   // been calculated for this frame.
+
   for (i=0; i<variables.size(); i++) variables[i]->cacheValue(true);
 
   for (axis_ctr = 0; axis_ctr < 3; axis_ctr++) {
     for (ctr=0; ctr < Coeff[axis_ctr].size(); ctr++) {
-      vFs(axis_ctr+1) += Coeff[axis_ctr][ctr]->GetValue();
+      vFnative(axis_ctr+1) += Coeff[axis_ctr][ctr]->GetValue();
     }
   }
 
-  // Calculate aerodynamic reference point shift, if any
-  if (AeroRPShift) {
-    vDeltaRP(eX) = AeroRPShift->GetValue()*Aircraft->Getcbar()*12.0;
+  // Note that we still need to convert to wind axes here, because it is
+  // used in the L/D calculation, and we still may want to look at Lift
+  // and Drag.
+
+  switch (axisType) {
+    case atBodyXYZ:       // Forces already in body axes; no manipulation needed
+      vFw = GetTb2w()*vFnative;
+      vForces = vFnative;
+      break;
+    case atLiftDrag:      // Copy forces into wind axes
+      vFw = vFnative;
+      vFw(eDrag)*=-1; vFw(eLift)*=-1;
+      vForces = GetTw2b()*vFw;
+      break;
+    case atAxialNormal:   // Convert native forces into Axial|Normal|Side system
+      vFw = GetTb2w()*vFnative;
+      vFnative(eX)*=-1; vFnative(eZ)*=-1;
+      vForces = vFnative;
+      break;
+    default:
+      cerr << endl << "  A proper axis type has NOT been selected. Check "
+                   << "your aerodynamics definition." << endl;
+      exit(-1);
   }
 
-  // calculate lift coefficient squared
+  // Calculate aerodynamic reference point shift, if any
+  if (AeroRPShift) vDeltaRP(eX) = AeroRPShift->GetValue()*Aircraft->Getcbar()*12.0;
+
+  // Calculate lift coefficient squared
   if ( Auxiliary->Getqbar() > 0) {
-    clsq = vFs(eLift) / (Aircraft->GetWingArea()*Auxiliary->Getqbar());
+    clsq = vFw(eLift) / (Aircraft->GetWingArea()*Auxiliary->Getqbar());
     clsq *= clsq;
   }
 
-  if ( vFs(eDrag)  > 0) {
-    lod = vFs(eLift) / vFs(eDrag);
-  }
-
-  //correct signs of drag and lift to wind axes convention
-  //positive forward, right, down
-  vFs(eDrag)*=-1; vFs(eLift)*=-1;
-
-  // transform stability axis forces into body axes
-  vForces = State->GetTs2b()*vFs;
+  // Calculate lift Lift over Drag
+  if ( fabs(vFw(eDrag)) > 0.0) lod = fabs( vFw(eLift) / vFw(eDrag) );
 
   vDXYZcg = MassBalance->StructuralToBody(Aircraft->GetXYZrp() + vDeltaRP);
 
@@ -193,37 +229,127 @@ bool FGAerodynamics::Run(void)
   return false;
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//
+// From Stevens and Lewis, "Aircraft Control and Simulation", 3rd Ed., the
+// transformation from body to wind axes is defined (where "a" is alpha and "B"
+// is beta):
+//
+//   cos(a)*cos(B)     sin(B)    sin(a)*cos(B)
+//  -cos(a)*sin(B)     cos(B)   -sin(a)*sin(B)
+//  -sin(a)              0       cos(a)
+//
+// The transform from wind to body axes is then,
+//
+//   cos(a)*cos(B)  -cos(a)*sin(B)  -sin(a)
+//          sin(B)          cos(B)     0
+//   sin(a)*cos(B)  -sin(a)*sin(B)   cos(a)
+
+FGMatrix33& FGAerodynamics::GetTw2b(void)
+{
+  double ca, cb, sa, sb;
+
+  double alpha = Auxiliary->Getalpha();
+  double beta  = Auxiliary->Getbeta();
+
+  ca = cos(alpha);
+  sa = sin(alpha);
+  cb = cos(beta);
+  sb = sin(beta);
+
+  mTw2b(1,1) = ca*cb;
+  mTw2b(1,2) = -ca*sb;
+  mTw2b(1,3) = -sa;
+  mTw2b(2,1) = sb;
+  mTw2b(2,2) = cb;
+  mTw2b(2,3) = 0.0;
+  mTw2b(3,1) = sa*cb;
+  mTw2b(3,2) = -sa*sb;
+  mTw2b(3,3) = ca;
+
+  return mTw2b;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGMatrix33& FGAerodynamics::GetTb2w(void)
+{
+  double alpha,beta;
+  double ca, cb, sa, sb;
+
+  alpha = Auxiliary->Getalpha();
+  beta  = Auxiliary->Getbeta();
+
+  ca = cos(alpha);
+  sa = sin(alpha);
+  cb = cos(beta);
+  sb = sin(beta);
+
+  mTb2w(1,1) = ca*cb;
+  mTb2w(1,2) = sb;
+  mTb2w(1,3) = sa*cb;
+  mTb2w(2,1) = -ca*sb;
+  mTb2w(2,2) = cb;
+  mTb2w(2,3) = -sa*sb;
+  mTb2w(3,1) = -sa;
+  mTb2w(3,2) = 0.0;
+  mTb2w(3,3) = ca;
+
+  return mTb2w;
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 bool FGAerodynamics::Load(Element *element)
 {
   string parameter, axis, scratch;
+  string scratch_unit="";
+  string fname="", file="";
   Element *temp_element, *axis_element, *function_element;
 
+  string separator = "/";
+#ifdef macintosh
+  separator = ";";
+#endif
+
+  fname = element->GetAttributeValue("file");
+  if (!fname.empty()) {
+    file = FDMExec->GetFullAircraftPath() + separator + fname;
+    document = LoadXMLDocument(file);
+  } else {
+    document = element;
+  }
+
+  DetermineAxisSystem(); // Detemine if Lift/Side/Drag, etc. is used.
+
   Debug(2);
 
-  if (temp_element = element->FindElement("alphalimits")) {
-    alphaclmin = temp_element->FindElementValueAsNumberConvertTo("min", "DEG");
-    alphaclmax = temp_element->FindElementValueAsNumberConvertTo("max", "DEG");
+  if (temp_element = document->FindElement("alphalimits")) {
+    scratch_unit = temp_element->GetAttributeValue("unit");
+    if (scratch_unit.empty()) scratch_unit = "RAD";
+    alphaclmin = temp_element->FindElementValueAsNumberConvertFromTo("min", scratch_unit, "RAD");
+    alphaclmax = temp_element->FindElementValueAsNumberConvertFromTo("max", scratch_unit, "RAD");
   }
 
-  if (temp_element = element->FindElement("hysteresis_limits")) {
-    alphahystmin = temp_element->FindElementValueAsNumberConvertTo("min", "DEG");
-    alphahystmax = temp_element->FindElementValueAsNumberConvertTo("max", "DEG");
+  if (temp_element = document->FindElement("hysteresis_limits")) {
+    scratch_unit = temp_element->GetAttributeValue("unit");
+    if (scratch_unit.empty()) scratch_unit = "RAD";
+    alphahystmin = temp_element->FindElementValueAsNumberConvertFromTo("min", scratch_unit, "RAD");
+    alphahystmax = temp_element->FindElementValueAsNumberConvertFromTo("max", scratch_unit, "RAD");
   }
 
-  if (temp_element = element->FindElement("aero_ref_pt_shift_x")) {
+  if (temp_element = document->FindElement("aero_ref_pt_shift_x")) {
     function_element = temp_element->FindElement("function");
     AeroRPShift = new FGFunction(PropertyManager, function_element);
   }
 
-  function_element = element->FindElement("function");
+  function_element = document->FindElement("function");
   while (function_element) {
     variables.push_back( new FGFunction(PropertyManager, function_element) );
-    function_element = element->FindNextElement("function");
+    function_element = document->FindNextElement("function");
   }
 
-  axis_element = element->FindElement("axis");
+  axis_element = document->FindElement("axis");
   while (axis_element) {
     CoeffArray ca;
     axis = axis_element->GetAttributeValue("name");
@@ -233,12 +359,60 @@ bool FGAerodynamics::Load(Element *element)
       function_element = axis_element->FindNextElement("function");
     }
     Coeff[AxisIdx[axis]] = ca;
-    axis_element = element->FindNextElement("axis");
+    axis_element = document->FindNextElement("axis");
   }
 
   return true;
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//
+// This private class function checks to verify consistency in the choice of
+// aerodynamic axes used in the config file. One set of LIFT|DRAG|SIDE, or 
+// X|Y|Z, or AXIAL|NORMAL|SIDE must be chosen; mixed system axes are not allowed.
+// Note that if the "SIDE" axis specifier is entered first in a config file, 
+// a warning message will be given IF the AXIAL|NORMAL specifiers are also given.
+// This is OK, and the warning is due to the SIDE specifier used for both
+// the Lift/Drag and Axial/Normal axis systems.
+
+void FGAerodynamics::DetermineAxisSystem()
+{
+  Element* axis_element = document->FindElement("axis");
+  string axis;
+  while (axis_element) {
+    axis = axis_element->GetAttributeValue("name");
+    if (axis == "LIFT" || axis == "DRAG" || axis == "SIDE") {
+      if (axisType == atNone) axisType = atLiftDrag;
+      else if (axisType != atLiftDrag) {
+        cerr << endl << "  Mixed aerodynamic axis systems have been used in the"
+                     << " aircraft config file." << endl;
+      }
+    } else if (axis == "AXIAL" || axis == "NORMAL") {
+      if (axisType == atNone) axisType = atAxialNormal;
+      else if (axisType != atAxialNormal) {
+        cerr << endl << "  Mixed aerodynamic axis systems have been used in the"
+                     << " aircraft config file." << endl;
+      }
+    } else if (axis == "X" || axis == "Y" || axis == "Z") {
+      if (axisType == atNone) axisType = atBodyXYZ;
+      else if (axisType != atBodyXYZ) {
+        cerr << endl << "  Mixed aerodynamic axis systems have been used in the"
+                     << " aircraft config file." << endl;
+      }
+    } else if (axis != "ROLL" && axis != "PITCH" && axis != "YAW") { // error
+      cerr << endl << "  An unknown axis type, " << axis << " has been specified"
+                   << " in the aircraft configuration file." << endl;
+      exit(-1);
+    }
+    axis_element = document->FindNextElement("axis");
+  }
+  if (axisType == atNone) {
+    axisType = atLiftDrag;
+    cerr << endl << "  The aerodynamic axis system has been set by default"
+                 << " to the Lift/Side/Drag system." << endl;
+  }
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 string FGAerodynamics::GetCoefficientStrings(string delimeter)
@@ -319,21 +493,21 @@ void FGAerodynamics::bind(void)
   PropertyManager->Tie("moments/n-aero-lbsft", this,3,
                        (PMF)&FGAerodynamics::GetMoments);
   PropertyManager->Tie("forces/fwx-aero-lbs", this,1,
-                       (PMF)&FGAerodynamics::GetvFs);
+                       (PMF)&FGAerodynamics::GetvFw);
   PropertyManager->Tie("forces/fwy-aero-lbs", this,2,
-                       (PMF)&FGAerodynamics::GetvFs);
+                       (PMF)&FGAerodynamics::GetvFw);
   PropertyManager->Tie("forces/fwz-aero-lbs", this,3,
-                       (PMF)&FGAerodynamics::GetvFs);
+                       (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-deg", this,
+  PropertyManager->Tie("aero/alpha-max-rad", this,
                        &FGAerodynamics::GetAlphaCLMax,
                        &FGAerodynamics::SetAlphaCLMax,
                        true);
-  PropertyManager->Tie("aero/alpha-min-deg", this,
+  PropertyManager->Tie("aero/alpha-min-rad", this,
                        &FGAerodynamics::GetAlphaCLMin,
                        &FGAerodynamics::SetAlphaCLMin,
                        true);
@@ -349,31 +523,6 @@ void FGAerodynamics::bind(void)
                         &FGAerodynamics::GetHysteresisParm);
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGAerodynamics::unbind(void)
-{
-  PropertyManager->Untie("forces/fbx-aero-lbs");
-  PropertyManager->Untie("forces/fby-aero-lbs");
-  PropertyManager->Untie("forces/fbz-aero-lbs");
-  PropertyManager->Untie("moments/l-aero-lbsft");
-  PropertyManager->Untie("moments/m-aero-lbsft");
-  PropertyManager->Untie("moments/n-aero-lbsft");
-  PropertyManager->Untie("forces/fwx-aero-lbs");
-  PropertyManager->Untie("forces/fwy-aero-lbs");
-  PropertyManager->Untie("forces/fwz-aero-lbs");
-  PropertyManager->Untie("forces/lod-norm");
-  PropertyManager->Untie("aero/cl-squared");
-  PropertyManager->Untie("aero/qbar-area");
-  PropertyManager->Untie("aero/alpha-max-deg");
-  PropertyManager->Untie("aero/alpha-min-deg");
-  PropertyManager->Untie("aero/bi2vel");
-  PropertyManager->Untie("aero/ci2vel");
-  PropertyManager->Untie("aero/alpha-wing-rad");
-  PropertyManager->Untie("aero/stall-hyst-norm");
-  PropertyManager->Untie("systems/stall-warn-norm");
-}
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
@@ -399,7 +548,17 @@ void FGAerodynamics::Debug(int from)
 
   if (debug_lvl & 1) { // Standard console startup message output
     if (from == 2) { // Loader
-      cout << endl << "  Aerodynamics: " << endl;
+      switch (axisType) {
+        case (atLiftDrag):
+          cout << endl << "  Aerodynamics (Lift|Side|Drag axes):" << endl << endl;
+          break;
+        case (atAxialNormal):
+          cout << endl << "  Aerodynamics (Axial|Side|Normal axes):" << endl << endl;
+          break;
+        case (atBodyXYZ):
+          cout << endl << "  Aerodynamics (X|Y|Z axes):" << endl << endl;
+          break;
+      }
     }
   }
   if (debug_lvl & 2 ) { // Instantiation/Destruction notification
index 91c19d122f5debc9a9ba1a1be9759743c0de0594..140816273b4432b5229454435287768563bc56bf 100644 (file)
@@ -55,6 +55,8 @@ INCLUDES
 #include "FGModel.h"
 #include <math/FGFunction.h>
 #include <math/FGColumnVector3.h>
+#include <math/FGMatrix33.h>
+#include <input_output/FGXMLFileRead.h>
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
@@ -80,22 +82,52 @@ CLASS DOCUMENTATION
 
     @code
     <aerodynamics>
-       <axis name="{LIFT|DRAG|SIDE|ROLL|PITCH|YAW}">
+       <alphalimits unit="{RAD | DEG}">
+         <min> {number} </min>
+         <max> {number} </max>
+       </alphalimits>
+       <hysteresis_limits unit="{RAD | DEG}">
+         <min> {number} </min>
+         <max> {number} </max>
+       </hysteresis_limits>
+       <aero_ref_pt_shift_x>  
+         <function>
+           {function contents}
+         </function> 
+       </aero_ref_pt_shift_x>  
+       <function>
+         {function contents}
+       </function>
+       <axis name="{LIFT | DRAG | SIDE | ROLL | PITCH | YAW}">
          {force coefficient definitions}
        </axis>
        {additional axis definitions}
     </aerodynamics>
     @endcode
 
+    Optionally two other coordinate systems may be used.<br><br>
+    1) Body coordinate system:
+    @code
+       <axis name="{X | Y | Z}">
+    @endcode
+    <br>
+    2) Axial-Normal coordinate system:
+    @code
+       <axis name="{AXIAL | NORMAL}">
+    @endcode
+    <br>
+    Systems may NOT be combined, or a load error will occur.
+
     @author Jon S. Berndt, Tony Peden
-    @Id $Revision$
+    @version $Revision$
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 CLASS DECLARATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-class FGAerodynamics : public FGModel {
+class FGAerodynamics : public FGModel, public FGXMLFileRead
+{
 
 public:
   /** Constructor
@@ -104,6 +136,8 @@ public:
   /// Destructor
   ~FGAerodynamics();
 
+  bool InitModel(void);
+
   /** Runs the Aerodynamics model; called by the Executive
       @return false if no error */
   bool Run(void);
@@ -134,15 +168,15 @@ public:
               similar call to GetForces(int n).*/
   double GetMoments(int n) const {return vMoments(n);}
 
-  /** Retrieves the aerodynamic forces in the stability axes.
-      @return a reference to a column vector containing the stability axis forces. */
-  FGColumnVector3& GetvFs(void) { return vFs; }
+  /** Retrieves the aerodynamic forces in the wind axes.
+      @return a reference to a column vector containing the wind axis forces. */
+  FGColumnVector3& GetvFw(void) { return vFw; }
 
-  /** Retrieves the aerodynamic forces in the stability axes, given an axis.
+  /** Retrieves the aerodynamic forces in the wind axes, given an axis.
       @param axis the axis to return the force for (eX, eY, eZ).
-      @return a reference to a column vector containing the requested stability
+      @return a reference to a column vector containing the requested wind
       axis force. */
-  double GetvFs(int axis) const { return vFs(axis); }
+  double GetvFw(int axis) const { return vFw(axis); }
 
   /** Retrieves the lift over drag ratio */
   inline double GetLoD(void) const { return lod; }
@@ -173,19 +207,34 @@ public:
       coefficients */
   string GetCoefficientValues(string delimeter);
 
+  /** Calculates and returns the wind-to-body axis transformation matrix.
+      @return a reference to the wind-to-body transformation matrix.
+      */
+  FGMatrix33& GetTw2b(void);
+
+  /** Calculates and returns the body-to-wind axis transformation matrix.
+      @return a reference to the wind-to-body transformation matrix.
+      */
+  FGMatrix33& GetTb2w(void);
+
+  vector <FGFunction*> * GetCoeff(void) const { return Coeff; }
+
 private:
+  enum eAxisType {atNone, atLiftDrag, atAxialNormal, atBodyXYZ} axisType;
   typedef map<string,int> AxisIndex;
   AxisIndex AxisIdx;
   FGFunction* AeroRPShift;
   vector <FGFunction*> variables;
   typedef vector <FGFunction*> CoeffArray;
   CoeffArray* Coeff;
-  FGColumnVector3 vFs;
+  FGColumnVector3 vFnative;
+  FGColumnVector3 vFw;
   FGColumnVector3 vForces;
   FGColumnVector3 vMoments;
-  FGColumnVector3 vLastFs;
   FGColumnVector3 vDXYZcg;
   FGColumnVector3 vDeltaRP;
+  FGMatrix33 mTw2b;
+  FGMatrix33 mTb2w;
   double alphaclmax, alphaclmin;
   double alphahystmax, alphahystmin;
   double impending_stall, stall_hyst;
@@ -193,8 +242,8 @@ private:
   double clsq, lod, qbar_area;
 
   typedef double (FGAerodynamics::*PMF)(int) const;
+  void DetermineAxisSystem(void);
   void bind(void);
-  void unbind(void);
 
   void Debug(int from);
 };
index edce3e0a3fbcb5b3ea15d9f452fdda8087557f68..c1d3ec86f0aa80cc711798c03be116f5bc615478 100644 (file)
@@ -62,8 +62,9 @@ INCLUDES
 #include "FGMassBalance.h"
 #include "FGInertial.h"
 #include "FGGroundReactions.h"
+#include "FGExternalReactions.h"
+#include "FGBuoyantForces.h"
 #include "FGAerodynamics.h"
-#include <FGState.h>
 #include <FGFDMExec.h>
 #include "FGPropagate.h"
 #include <input_output/FGPropertyManager.h>
@@ -105,12 +106,20 @@ FGAircraft::FGAircraft(FGFDMExec* fdmex) : FGModel(fdmex)
 
 FGAircraft::~FGAircraft()
 {
-  unbind();
   Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGAircraft::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGAircraft::Run(void)
 {
   if (FGModel::Run()) return true;
@@ -121,6 +130,8 @@ bool FGAircraft::Run(void)
     vForces += Aerodynamics->GetForces();
     vForces += Propulsion->GetForces();
     vForces += GroundReactions->GetForces();
+    vForces += ExternalReactions->GetForces();
+    vForces += BuoyantForces->GetForces();
   }
 
   vMoments.InitMatrix();
@@ -128,13 +139,15 @@ bool FGAircraft::Run(void)
     vMoments += Aerodynamics->GetMoments();
     vMoments += Propulsion->GetMoments();
     vMoments += GroundReactions->GetMoments();
+    vMoments += ExternalReactions->GetMoments();
+    vMoments += BuoyantForces->GetMoments();
   }
 
   vBodyAccel = vForces/MassBalance->GetMass();
 
   vNcg = vBodyAccel/Inertial->gravity();
 
-  vNwcg = State->GetTb2s() * vNcg;
+  vNwcg = Aerodynamics->GetTb2w() * vNcg;
   vNwcg(3) = -1*vNwcg(3) + 1;
 
   return false;
@@ -144,7 +157,7 @@ bool FGAircraft::Run(void)
 
 double FGAircraft::GetNlf(void)
 {
-  return -1*Aerodynamics->GetvFs(3)/MassBalance->GetWeight();
+  return -1*Aerodynamics->GetvFw(3)/MassBalance->GetWeight();
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -161,7 +174,7 @@ bool FGAircraft::Load(Element* el)
   if (el->FindElement("chord"))
     cbar = el->FindElementValueAsNumberConvertTo("chord", "FT");
   if (el->FindElement("wing_incidence"))
-    WingIncidence = el->FindElementValueAsNumberConvertTo("wing_incidence", "DEG");
+    WingIncidence = el->FindElementValueAsNumberConvertTo("wing_incidence", "RAD");
   if (el->FindElement("htailarea"))
     HTailArea = el->FindElementValueAsNumberConvertTo("htailarea", "FT2");
   if (el->FindElement("htailarm"))
@@ -191,7 +204,7 @@ bool FGAircraft::Load(Element* el)
     lbarv = VTailArm/cbar;
     if (WingArea != 0.0) {
       vbarh = HTailArm*HTailArea / (cbar*WingArea);
-      vbarv = VTailArm*VTailArea / (cbar*WingArea);
+      vbarv = VTailArm*VTailArea / (WingSpan*WingArea);
     }
   }
 
@@ -205,10 +218,11 @@ bool FGAircraft::Load(Element* el)
 void FGAircraft::bind(void)
 {
   typedef double (FGAircraft::*PMF)(int) const;
-  PropertyManager->Tie("metrics/Sw-sqft", this, &FGAircraft::GetWingArea);
+  PropertyManager->Tie("metrics/Sw-sqft", this, &FGAircraft::GetWingArea, &FGAircraft::SetWingArea);
   PropertyManager->Tie("metrics/bw-ft", this, &FGAircraft::GetWingSpan);
   PropertyManager->Tie("metrics/cbarw-ft", this, &FGAircraft::Getcbar);
-  PropertyManager->Tie("metrics/iw-deg", this, &FGAircraft::GetWingIncidence);
+  PropertyManager->Tie("metrics/iw-rad", this, &FGAircraft::GetWingIncidence);
+  PropertyManager->Tie("metrics/iw-deg", this, &FGAircraft::GetWingIncidenceDeg);
   PropertyManager->Tie("metrics/Sh-sqft", this, &FGAircraft::GetHTailArea);
   PropertyManager->Tie("metrics/lh-ft", this, &FGAircraft::GetHTailArm);
   PropertyManager->Tie("metrics/Sv-sqft", this, &FGAircraft::GetVTailArea);
@@ -235,40 +249,6 @@ void FGAircraft::bind(void)
   PropertyManager->Tie("metrics/visualrefpoint-z-in", this, eZ, (PMF)&FGAircraft::GetXYZvrp);
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGAircraft::unbind(void)
-{
-  PropertyManager->Untie("metrics/Sw-sqft");
-  PropertyManager->Untie("metrics/bw-ft");
-  PropertyManager->Untie("metrics/cbarw-ft");
-  PropertyManager->Untie("metrics/iw-deg");
-  PropertyManager->Untie("metrics/Sh-sqft");
-  PropertyManager->Untie("metrics/lh-ft");
-  PropertyManager->Untie("metrics/Sv-sqft");
-  PropertyManager->Untie("metrics/lv-ft");
-  PropertyManager->Untie("metrics/lh-norm");
-  PropertyManager->Untie("metrics/lv-norm");
-  PropertyManager->Untie("metrics/vbarh-norm");
-  PropertyManager->Untie("metrics/vbarv-norm");
-  PropertyManager->Untie("moments/l-total-lbsft");
-  PropertyManager->Untie("moments/m-total-lbsft");
-  PropertyManager->Untie("moments/n-total-lbsft");
-  PropertyManager->Untie("forces/fbx-total-lbs");
-  PropertyManager->Untie("forces/fby-total-lbs");
-  PropertyManager->Untie("forces/fbz-total-lbs");
-  PropertyManager->Untie("forces/hold-down");
-  PropertyManager->Untie("metrics/aero-rp-x-in");
-  PropertyManager->Untie("metrics/aero-rp-y-in");
-  PropertyManager->Untie("metrics/aero-rp-z-in");
-  PropertyManager->Untie("metrics/eyepoint-x-in");
-  PropertyManager->Untie("metrics/eyepoint-y-in");
-  PropertyManager->Untie("metrics/eyepoint-z-in");
-  PropertyManager->Untie("metrics/visualrefpoint-x-in");
-  PropertyManager->Untie("metrics/visualrefpoint-y-in");
-  PropertyManager->Untie("metrics/visualrefpoint-z-in");
-}
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index f62ef276a5c56ba306c1ae110ccab040b94268b0..485d0efd33574c0e1a7b48b6e3e73f48e3ddcf8a 100644 (file)
@@ -42,14 +42,11 @@ INCLUDES
 #  include <simgear/compiler.h>
 #  ifdef SG_HAVE_STD_INCLUDES
 #    include <vector>
-#    include <iterator>
 #  else
 #    include <vector.h>
-#    include <iterator.h>
 #  endif
 #else
 #  include <vector>
-#  include <iterator>
 #endif
 
 #include "FGModel.h"
@@ -73,11 +70,33 @@ CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 /** Encapsulates an Aircraft and its systems.
-    Owns all the parts (other classes) which make up this aircraft. This includes
+<p> Owns all the parts (other classes) which make up this aircraft. This includes
     the Engines, Tanks, Propellers, Nozzles, Aerodynamic and Mass properties,
     landing gear, etc. These constituent parts may actually run as separate
     JSBSim models themselves, but the responsibility for initializing them and
     for retrieving their force and moment contributions falls to FGAircraft.
+<p> The \<metrics> section of the aircraft configuration file is read here, and
+    the metrical information is held by this class.
+<h3>Configuration File Format for \<metrics> Section:</h3>
+@code
+    <metrics>
+        <wingarea unit="{FT2 | M2}"> {number} </wingarea>
+        <wingspan unit="{FT | M}"> {number} </wingspan>
+        <chord unit="{FT | M}"> {number} </chord>
+        <htailarea unit="{FT2 | M2}"> {number} </htailarea>
+        <htailarm unit="{FT | M}"> {number} </htailarm>
+        <vtailarea unit="{FT2 | M}"> {number} </vtailarea>
+        <vtailarm unit="{FT | M}"> {number} </vtailarm>
+        <wing_incidence unit="{RAD | DEG}"> {number} </wing_incidence>
+        <location name="{AERORP | EYEPOINT | VRP}" unit="{IN | M}">
+            <x> {number} </x>
+            <y> {number} </y>
+            <z> {number} </z>
+        </location>
+        {other location blocks}
+    </metrics>
+@endcode
+
     @author Jon S. Berndt
     @version $Id$
     @see Cooke, Zyda, Pratt, and McGhee, "NPSNET: Flight Simulation Dynamic Modeling
@@ -111,6 +130,8 @@ public:
       @return false if no error */
   bool Run(void);
 
+  bool InitModel(void);
+
   /** Loads the aircraft.
       The executive calls this method to load the aircraft into JSBSim.
       @param el a pointer to the element tree
@@ -128,6 +149,7 @@ public:
   /// Gets the average wing chord
   double Getcbar(void) const { return cbar; }
   inline double GetWingIncidence(void) const { return WingIncidence; }
+  inline double GetWingIncidenceDeg(void) const { return WingIncidence*radtodeg; }
   inline double GetHTailArea(void) const { return HTailArea; }
   inline double GetHTailArm(void)  const { return HTailArm; }
   inline double GetVTailArea(void) const { return VTailArea; }
@@ -156,6 +178,8 @@ public:
 
   void SetXYZrp(int idx, double value) {vXYZrp(idx) = value;}
 
+  void SetWingArea(double S) {WingArea = S;}
+
   double GetNlf(void);
 
   inline FGColumnVector3& GetNwcg(void) { return vNwcg; }
index 8c4712b5557b9e83d299812011409570eb4a9f51..95afb809274b0fef8548ba8d241eee7f23960de2 100644 (file)
@@ -81,15 +81,18 @@ FGAtmosphere::FGAtmosphere(FGFDMExec* fdmex) : FGModel(fdmex)
   htab[7]=259186.352; //ft.
 
   MagnitudedAccelDt = MagnitudeAccel = Magnitude = 0.0;
-//   turbType = ttNone;
-  turbType = ttStandard;
-//   turbType = ttBerndt;
+  SetTurbType( ttCulp );
   TurbGain = 0.0;
-  TurbRate = 1.0;
+  TurbRate = 1.7;
+  Rhythmicity = 0.1;
+  spike = target_time = strength = 0.0;
+  wind_from_clockwise = 0.0;
 
   T_dev_sl = T_dev = delta_T = 0.0;
   StandardTempOnly = false;
   first_pass = true;
+  vGustNED(1) = vGustNED(2) = vGustNED(3) = 0.0; bgustSet = false;
+  vTurbulence(1) = vTurbulence(2) = vTurbulence(3) = 0.0;
 
   bind();
   Debug(0);
@@ -99,7 +102,6 @@ FGAtmosphere::FGAtmosphere(FGFDMExec* fdmex) : FGModel(fdmex)
 
 FGAtmosphere::~FGAtmosphere()
 {
-  unbind();
   Debug(1);
 }
 
@@ -107,7 +109,7 @@ FGAtmosphere::~FGAtmosphere()
 
 bool FGAtmosphere::InitModel(void)
 {
-  FGModel::InitModel();
+  if (!FGModel::InitModel()) return false;
 
   UseInternal();  // this is the default
 
@@ -152,9 +154,8 @@ bool FGAtmosphere::Run(void)
 void FGAtmosphere::Calculate(double altitude)
 {
   double slope, reftemp, refpress;
-  int i = 0;
+  int i = lastIndex;
 
-  i = lastIndex;
   if (altitude < htab[lastIndex]) {
     if (altitude <= 0) {
       i = 0;
@@ -262,9 +263,9 @@ void FGAtmosphere::CalculateDerived(void)
   T_dev = (*temperature) - GetTemperature(h);
   density_altitude = h + T_dev * 66.7;
 
-  if (turbType == ttStandard) {
+  if (turbType == ttStandard || ttCulp) {
     Turbulence();
-    vWindNED += vTurbulence;
+    vWindNED += vGustNED + vTurbulence;
   }
   if (vWindNED(1) != 0.0) psiw = atan2( vWindNED(2), vWindNED(1) );
   if (psiw < 0) psiw += 2*M_PI;
@@ -330,6 +331,8 @@ void FGAtmosphere::Turbulence(void)
 {
   switch (turbType) {
   case ttStandard: {
+    TurbGain = TurbGain * TurbGain * 100.0;
+
     vDirectiondAccelDt(eX) = 1 - 2.0*(double(rand())/double(RAND_MAX));
     vDirectiondAccelDt(eY) = 1 - 2.0*(double(rand())/double(RAND_MAX));
     vDirectiondAccelDt(eZ) = 1 - 2.0*(double(rand())/double(RAND_MAX));
@@ -341,6 +344,7 @@ void FGAtmosphere::Turbulence(void)
                          (1 + fabs(Magnitude)));
     MagnitudeAccel    += MagnitudedAccelDt*rate*TurbRate*State->Getdt();
     Magnitude         += MagnitudeAccel*rate*State->Getdt();
+    Magnitude          = fabs(Magnitude);
 
     vDirectiondAccelDt.Normalize();
 
@@ -361,8 +365,15 @@ void FGAtmosphere::Turbulence(void)
     if (HOverBMAC < 3.0)
         vTurbulence *= (HOverBMAC / 3.0) * (HOverBMAC / 3.0);
 
-    vTurbulenceGrad = TurbGain*MagnitudeAccel * vDirection;
+    // I don't believe these next two statements calculate the proper gradient over
+    // the aircraft body. One reason is because this has no relationship with the
+    // orientation or velocity of the aircraft, which it must have. What is vTurbulenceGrad
+    // supposed to represent? And the direction and magnitude of the turbulence can change,
+    // so both accelerations need to be accounted for, no?
+
+    // Need to determine the turbulence change in body axes between two time points.
 
+    vTurbulenceGrad = TurbGain*MagnitudeAccel * vDirection;
     vBodyTurbGrad = Propagate->GetTl2b()*vTurbulenceGrad;
 
     if (Aircraft->GetWingSpan() > 0) {
@@ -384,12 +395,16 @@ void FGAtmosphere::Turbulence(void)
                                 // actually felt by the plane, now
                                 // that we've used them to calculate
                                 // moments.
-    vTurbulence(eX) = 0.0;
-    vTurbulence(eY) = 0.0;
+                                // Why? (JSB)
+//    vTurbulence(eX) = 0.0;
+//    vTurbulence(eY) = 0.0;
 
     break;
   }
-  case ttBerndt: {
+  case ttBerndt: { // This is very experimental and incomplete at the moment.
+
+    TurbGain = TurbGain * TurbGain * 100.0;
+  
     vDirectiondAccelDt(eX) = 1 - 2.0*(double(rand())/double(RAND_MAX));
     vDirectiondAccelDt(eY) = 1 - 2.0*(double(rand())/double(RAND_MAX));
     vDirectiondAccelDt(eZ) = 1 - 2.0*(double(rand())/double(RAND_MAX));
@@ -429,6 +444,56 @@ void FGAtmosphere::Turbulence(void)
 
     break;
   }
+  case ttCulp: { 
+
+    vTurbPQR(eP) = wind_from_clockwise;
+    if (TurbGain == 0.0) return;
+  
+    // keep the inputs within allowable limts for this model
+    if (TurbGain < 0.0) TurbGain = 0.0;
+    if (TurbGain > 1.0) TurbGain = 1.0;
+    if (TurbRate < 0.0) TurbRate = 0.0;
+    if (TurbRate > 30.0) TurbRate = 30.0;
+    if (Rhythmicity < 0.0) Rhythmicity = 0.0;
+    if (Rhythmicity > 1.0) Rhythmicity = 1.0;
+
+    // generate a sine wave corresponding to turbulence rate in hertz
+    double time = FDMExec->GetSimTime();
+    double sinewave = sin( time * TurbRate * 6.283185307 );
+
+    double random = 0.0;
+    if (target_time == 0.0) {
+      strength = random = 1 - 2.0*(double(rand())/double(RAND_MAX));
+      target_time = time + 0.71 + (random * 0.5);
+    }
+    if (time > target_time) {
+      spike = 1.0;
+      target_time = 0.0;
+    }    
+
+    // max vertical wind speed in fps, corresponds to TurbGain = 1.0
+    double max_vs = 40;
+
+    vTurbulence(1) = vTurbulence(2) = vTurbulence(3) = 0.0;
+    double delta = strength * max_vs * TurbGain * (1-Rhythmicity) * spike;
+
+    // Vertical component of turbulence.
+    vTurbulence(3) = sinewave * max_vs * TurbGain * Rhythmicity;
+    vTurbulence(3)+= delta;
+    double HOverBMAC = Auxiliary->GetHOverBMAC();
+    if (HOverBMAC < 3.0)
+        vTurbulence(3) *= HOverBMAC * 0.3333;
+    // Yaw component of turbulence.
+    vTurbulence(1) = sin( delta * 3.0 );
+    vTurbulence(2) = cos( delta * 3.0 );
+
+    // Roll component of turbulence. Clockwise vortex causes left roll.
+    vTurbPQR(eP) += delta * 0.04;
+
+    spike = spike * 0.9;
+    break;
+  }
   default:
     break;
   }
@@ -460,6 +525,7 @@ void FGAtmosphere::bind(void)
 {
   typedef double (FGAtmosphere::*PMF)(int) const;
   typedef double (FGAtmosphere::*PMFv)(void) const;
+  typedef void   (FGAtmosphere::*PMFd)(int,double);
   PropertyManager->Tie("atmosphere/T-R", this, (PMFv)&FGAtmosphere::GetTemperature);
   PropertyManager->Tie("atmosphere/rho-slugs_ft3", this, (PMFv)&FGAtmosphere::GetDensity);
   PropertyManager->Tie("atmosphere/P-psf", this, (PMFv)&FGAtmosphere::GetPressure);
@@ -479,31 +545,18 @@ void FGAtmosphere::bind(void)
   PropertyManager->Tie("atmosphere/p-turb-rad_sec", this,1, (PMF)&FGAtmosphere::GetTurbPQR);
   PropertyManager->Tie("atmosphere/q-turb-rad_sec", this,2, (PMF)&FGAtmosphere::GetTurbPQR);
   PropertyManager->Tie("atmosphere/r-turb-rad_sec", this,3, (PMF)&FGAtmosphere::GetTurbPQR);
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGAtmosphere::unbind(void)
-{
-  PropertyManager->Untie("atmosphere/T-R");
-  PropertyManager->Untie("atmosphere/rho-slugs_ft3");
-  PropertyManager->Untie("atmosphere/P-psf");
-  PropertyManager->Untie("atmosphere/a-fps");
-  PropertyManager->Untie("atmosphere/T-sl-R");
-  PropertyManager->Untie("atmosphere/rho-sl-slugs_ft3");
-  PropertyManager->Untie("atmosphere/P-sl-psf");
-  PropertyManager->Untie("atmosphere/a-sl-fps");
-  PropertyManager->Untie("atmosphere/delta-T");
-  PropertyManager->Untie("atmosphere/T-sl-dev-F");
-  PropertyManager->Untie("atmosphere/density-altitude");
-  PropertyManager->Untie("atmosphere/theta");
-  PropertyManager->Untie("atmosphere/sigma");
-  PropertyManager->Untie("atmosphere/delta");
-  PropertyManager->Untie("atmosphere/a-ratio");
-  PropertyManager->Untie("atmosphere/psiw-rad");
-  PropertyManager->Untie("atmosphere/p-turb-rad_sec");
-  PropertyManager->Untie("atmosphere/q-turb-rad_sec");
-  PropertyManager->Untie("atmosphere/r-turb-rad_sec");
+  PropertyManager->Tie("atmosphere/turb-rate", this, &FGAtmosphere::GetTurbRate, &FGAtmosphere::SetTurbRate);
+  PropertyManager->Tie("atmosphere/turb-gain", this, &FGAtmosphere::GetTurbGain, &FGAtmosphere::SetTurbGain);
+  PropertyManager->Tie("atmosphere/turb-rhythmicity", this, &FGAtmosphere::GetRhythmicity,
+                                                            &FGAtmosphere::SetRhythmicity);
+  PropertyManager->Tie("atmosphere/gust-north-fps", this,1, (PMF)&FGAtmosphere::GetGustNED,
+                                                          (PMFd)&FGAtmosphere::SetGustNED);
+  PropertyManager->Tie("atmosphere/gust-east-fps",  this,2, (PMF)&FGAtmosphere::GetGustNED,
+                                                          (PMFd)&FGAtmosphere::SetGustNED);
+  PropertyManager->Tie("atmosphere/gust-down-fps",  this,3, (PMF)&FGAtmosphere::GetGustNED,
+                                                          (PMFd)&FGAtmosphere::SetGustNED);
+  PropertyManager->Tie("atmosphere/wind-from-cw", this, &FGAtmosphere::GetWindFromClockwise,
+                                                        &FGAtmosphere::SetWindFromClockwise);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index 12e7af38fa3421c4fa88911c98765594361704a8..4434c31791e39aebbd5c27c4fa1880142b69e66d 100644 (file)
@@ -61,7 +61,7 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Models the standard atmosphere.
+/** Models the 1976 Standard Atmosphere.
     @author Tony Peden, Jon Berndt
     @version $Id$
     @see Anderson, John D. "Introduction to Flight, Third Edition", McGraw-Hill,
@@ -83,6 +83,7 @@ public:
       @return false if no error */
   bool Run(void);
   bool InitModel(void);
+  enum tType {ttStandard, ttBerndt, ttCulp, ttNone} turbType;
 
   /// Returns the temperature in degrees Rankine.
   inline double GetTemperature(void) const {return *temperature;}
@@ -94,9 +95,9 @@ public:
   /// Returns the standard pressure at a specified altitude
   double GetPressure(double altitude);
   /// Returns the standard temperature at a specified altitude
-  inline double GetTemperature(double altitude);
+  double GetTemperature(double altitude);
   /// Returns the standard density at a specified altitude
-  inline double GetDensity(double altitude);
+  double GetDensity(double altitude);
   /// Returns the speed of sound in ft/sec.
   inline double GetSoundSpeed(void) const {return soundspeed;}
 
@@ -151,26 +152,46 @@ public:
   /// Retrieves the wind components in NED frame.
   inline FGColumnVector3& GetWindNED(void) { return vWindNED; }
 
+  /// Sets gust components in NED frame.
+  inline void SetGustNED(int idx, double gust) { vGustNED(idx)=gust;}
+
+  /// Retrieves the gust components in NED frame.
+  inline double GetGustNED(int idx) const {return vGustNED(idx);}
+
+  /// Retrieves the gust components in NED frame.
+  inline FGColumnVector3& GetGustNED(void) {return vGustNED;}
+
   /** Retrieves the wind direction. The direction is defined as north=0 and
       increases counterclockwise. The wind heading is returned in radians.*/
   inline double GetWindPsi(void) const { return psiw; }
 
-  inline void SetTurbGain(double tt) {TurbGain = tt;}
-  inline void SetTurbRate(double tt) {TurbRate = tt;}
+  /** Turbulence models available: ttStandard, ttBerndt, ttCulp, ttNone */
+  inline void   SetTurbType(tType tt) {turbType = tt;}
+  inline tType  GetTurbType() const {return turbType;}
 
-  inline double GetTurbPQR(int idx) const {return vTurbPQR(idx);}
-  inline FGColumnVector3& GetTurbPQR(void) {return vTurbPQR;}
+  inline void   SetTurbGain(double tg) {TurbGain = tg;}
+  inline double GetTurbGain() const {return TurbGain;}
 
-  void bind(void);
-  void unbind(void);
+  inline void   SetTurbRate(double tr) {TurbRate = tr;}
+  inline double GetTurbRate() const {return TurbRate;}
+
+  inline void   SetRhythmicity(double r) {Rhythmicity=r;}
+  inline double GetRhythmicity() const {return Rhythmicity;}
 
+  /** Sets wind vortex, clockwise as seen from a point in front of aircraft,
+      looking aft. Units are radians/second. */
+  inline void   SetWindFromClockwise(double wC) { wind_from_clockwise=wC; }
+  inline double GetWindFromClockwise(void) const {return wind_from_clockwise;}
+
+  inline double GetTurbPQR(int idx) const {return vTurbPQR(idx);}
+  double GetTurbMagnitude(void) const {return Magnitude;}
+  FGColumnVector3& GetTurbDirection(void) {return vDirection;}
+  inline FGColumnVector3& GetTurbPQR(void) {return vTurbPQR;}
 
 protected:
   double rho;
 
-  enum tType {ttStandard, ttBerndt, ttNone} turbType;
   struct atmType {double Temperature; double Pressure; double Density;};
-
   int lastIndex;
   double h;
   double htab[8];
@@ -190,6 +211,9 @@ protected:
   double MagnitudedAccelDt, MagnitudeAccel, Magnitude;
   double TurbGain;
   double TurbRate;
+  double Rhythmicity;
+  double wind_from_clockwise;
+  double spike, target_time, strength;
   FGColumnVector3 vDirectiondAccelDt;
   FGColumnVector3 vDirectionAccel;
   FGColumnVector3 vDirection;
@@ -201,6 +225,9 @@ protected:
   FGColumnVector3 vWindNED;
   double psiw;
 
+  FGColumnVector3 vGustNED;
+  bool bgustSet;
+
   /// Calculate the atmosphere for the given altitude, including effects of temperature deviation.
   void Calculate(double altitude);
   /// Calculate atmospheric properties other than the basic T, P and rho.
@@ -208,6 +235,7 @@ protected:
   /// Get T, P and rho for a standard atmosphere at the given altitude.
   void GetStdAtmosphere(double altitude);
   void Turbulence(void);
+  void bind(void);
   void Debug(int from);
 };
 
index bc684ce9cabc2c6388f2203712239b34fe4ea6bc..fdde24a97d76dee53d2d4e0614f245f614600873 100755 (executable)
@@ -44,10 +44,13 @@ INCLUDES
 #include "FGAerodynamics.h"
 #include "FGPropagate.h"
 #include "FGAtmosphere.h"
-#include <FGState.h>
 #include <FGFDMExec.h>
 #include "FGAircraft.h"
 #include "FGInertial.h"
+#include "FGExternalReactions.h"
+#include "FGBuoyantForces.h"
+#include "FGGroundReactions.h"
+#include "FGPropulsion.h"
 #include <input_output/FGPropertyManager.h>
 
 namespace JSBSim {
@@ -65,7 +68,6 @@ FGAuxiliary::FGAuxiliary(FGFDMExec* fdmex) : FGModel(fdmex)
   Name = "FGAuxiliary";
   vcas = veas = pt = tat = 0;
   psl = rhosl = 1;
-  earthPosAngle = 0.0;
   qbar = 0;
   qbarUW = 0.0;
   qbarUV = 0.0;
@@ -91,9 +93,37 @@ FGAuxiliary::FGAuxiliary(FGFDMExec* fdmex) : FGModel(fdmex)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGAuxiliary::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  vcas = veas = pt = tat = 0;
+  psl = rhosl = 1;
+  qbar = 0;
+  qbarUW = 0.0;
+  qbarUV = 0.0;
+  Mach = 0.0;
+  alpha = beta = 0.0;
+  adot = bdot = 0.0;
+  gamma = Vt = Vground = 0.0;
+  psigt = 0.0;
+  day_of_year = 1;
+  seconds_in_day = 0.0;
+  hoverbmac = hoverbcg = 0.0;
+
+  vPilotAccel.InitMatrix();
+  vPilotAccelN.InitMatrix();
+  vToEyePt.InitMatrix();
+  vAeroPQR.InitMatrix();
+  vEulerRates.InitMatrix();
+
+  return true;
+}
+  
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 FGAuxiliary::~FGAuxiliary()
 {
-  unbind();
   Debug(1);
 }
 
@@ -139,10 +169,10 @@ bool FGAuxiliary::Run()
   } else if (GroundReactions->GetWOW() && vUVW(eU) < 30) {
     double factor = (vUVW(eU) - 10.0)/20.0;
     vAeroPQR = vPQR + factor*Atmosphere->GetTurbPQR();
-    vAeroUVW = vUVW + factor*Propagate->GetTl2b()*Atmosphere->GetWindNED();
+    vAeroUVW = vUVW + factor*Propagate->GetTl2b()*(Atmosphere->GetWindNED()+Atmosphere->GetGustNED());
   } else {
     vAeroPQR = vPQR + Atmosphere->GetTurbPQR();
-    vAeroUVW = vUVW + Propagate->GetTl2b()*Atmosphere->GetWindNED();
+    vAeroUVW = vUVW + Propagate->GetTl2b()*(Atmosphere->GetWindNED()+Atmosphere->GetGustNED());
   }
 
   Vt = vAeroUVW.Magnitude();
@@ -208,12 +238,17 @@ bool FGAuxiliary::Run()
 
   vPilotAccel.InitMatrix();
   if ( Vt > 1.0 ) {
-     vPilotAccel =  Aerodynamics->GetForces()
-                    +  Propulsion->GetForces()
-                    +  GroundReactions->GetForces();
-     vPilotAccel /= MassBalance->GetMass();
+     vAircraftAccel = Aerodynamics->GetForces()
+                    + Propulsion->GetForces()
+                    + GroundReactions->GetForces()
+                    + ExternalReactions->GetForces()
+                    + BuoyantForces->GetForces();
+
+     vAircraftAccel /= MassBalance->GetMass();
+     // Nz is Acceleration in "g's", along normal axis (-Z body axis)
+     Nz = -vAircraftAccel(eZ)/Inertial->gravity();
      vToEyePt = MassBalance->StructuralToBody(Aircraft->GetXYZep());
-     vPilotAccel += Propagate->GetPQRdot() * vToEyePt;
+     vPilotAccel = vAircraftAccel + Propagate->GetPQRdot() * vToEyePt;
      vPilotAccel += vPQR * (vPQR * vToEyePt);
   } else {
      // The line below handles low velocity (and on-ground) cases, basically
@@ -223,12 +258,11 @@ bool FGAuxiliary::Run()
      // this branch could be eliminated, with a penalty of having a short
      // transient at startup (lasting only a fraction of a second).
      vPilotAccel = Propagate->GetTl2b() * FGColumnVector3( 0.0, 0.0, -Inertial->gravity() );
+     Nz = -vPilotAccel(eZ)/Inertial->gravity();
   }
 
   vPilotAccelN = vPilotAccel/Inertial->gravity();
 
-  earthPosAngle += State->Getdt()*Inertial->omega();
-
   // VRP computation
   const FGLocation& vLocation = Propagate->GetLocation();
   FGColumnVector3 vrpStructural = Aircraft->GetXYZvrp();
@@ -242,12 +276,17 @@ bool FGAuxiliary::Run()
   FGColumnVector3 vMac = Propagate->GetTb2l()*MassBalance->StructuralToBody(Aircraft->GetXYZrp());
   hoverbmac = (Propagate->GetDistanceAGL() + vMac(3)) / Aircraft->GetWingSpan();
 
+  // when all model are executed, 
+  // please calculate the distance from the initial point
+
+  CalculateRelativePosition();
+
   return false;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-double FGAuxiliary::GetHeadWind(void)
+double FGAuxiliary::GetHeadWind(void) const
 {
   double psiw,vw;
 
@@ -259,7 +298,7 @@ double FGAuxiliary::GetHeadWind(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-double FGAuxiliary::GetCrossWind(void)
+double FGAuxiliary::GetCrossWind(void) const
 {
   double psiw,vw;
 
@@ -301,7 +340,7 @@ void FGAuxiliary::bind(void)
   PropertyManager->Tie("accelerations/n-pilot-x-norm", this, eX, (PMF)&FGAuxiliary::GetNpilot);
   PropertyManager->Tie("accelerations/n-pilot-y-norm", this, eY, (PMF)&FGAuxiliary::GetNpilot);
   PropertyManager->Tie("accelerations/n-pilot-z-norm", this, eZ, (PMF)&FGAuxiliary::GetNpilot);
-  PropertyManager->Tie("position/epa-rad", this, &FGAuxiliary::GetEarthPositionAngle);
+  PropertyManager->Tie("accelerations/Nz", this, &FGAuxiliary::GetNz);
   /* PropertyManager->Tie("atmosphere/headwind-fps", this, &FGAuxiliary::GetHeadWind, true);
   PropertyManager->Tie("atmosphere/crosswind-fps", this, &FGAuxiliary::GetCrossWind, true); */
   PropertyManager->Tie("aero/alpha-rad", this, (PF)&FGAuxiliary::Getalpha, &FGAuxiliary::Setalpha, true);
@@ -321,60 +360,21 @@ void FGAuxiliary::bind(void)
   PropertyManager->Tie("aero/h_b-mac-ft", this, &FGAuxiliary::GetHOverBMAC);
   PropertyManager->Tie("flight-path/gamma-rad", this, &FGAuxiliary::GetGamma, &FGAuxiliary::SetGamma);
   PropertyManager->Tie("flight-path/psi-gt-rad", this, &FGAuxiliary::GetGroundTrack);
+
+  PropertyManager->Tie("position/distance-from-start-lon-mt", this, &FGAuxiliary::GetLongitudeRelativePosition);
+  PropertyManager->Tie("position/distance-from-start-lat-mt", this, &FGAuxiliary::GetLatitudeRelativePosition);
+  PropertyManager->Tie("position/distance-from-start-mag-mt", this, &FGAuxiliary::GetDistanceRelativePosition);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGAuxiliary::unbind(void)
-{
-  PropertyManager->Untie("propulsion/tat-r");
-  PropertyManager->Untie("propulsion/tat-c");
-  PropertyManager->Untie("propulsion/pt-lbs_sqft");
-
-  PropertyManager->Untie("velocities/vc-fps");
-  PropertyManager->Untie("velocities/vc-kts");
-  PropertyManager->Untie("velocities/ve-fps");
-  PropertyManager->Untie("velocities/ve-kts");
-  PropertyManager->Untie("velocities/machU");
-  PropertyManager->Untie("velocities/p-aero-rad_sec");
-  PropertyManager->Untie("velocities/q-aero-rad_sec");
-  PropertyManager->Untie("velocities/r-aero-rad_sec");
-  PropertyManager->Untie("velocities/phidot-rad_sec");
-  PropertyManager->Untie("velocities/thetadot-rad_sec");
-  PropertyManager->Untie("velocities/psidot-rad_sec");
-  PropertyManager->Untie("velocities/u-aero-fps");
-  PropertyManager->Untie("velocities/v-aero-fps");
-  PropertyManager->Untie("velocities/w-aero-fps");
-  PropertyManager->Untie("velocities/vt-fps");
-  PropertyManager->Untie("velocities/mach");
-  PropertyManager->Untie("velocities/vg-fps");
-  PropertyManager->Untie("accelerations/a-pilot-x-ft_sec2");
-  PropertyManager->Untie("accelerations/a-pilot-y-ft_sec2");
-  PropertyManager->Untie("accelerations/a-pilot-z-ft_sec2");
-  PropertyManager->Untie("accelerations/n-pilot-x-norm");
-  PropertyManager->Untie("accelerations/n-pilot-y-norm");
-  PropertyManager->Untie("accelerations/n-pilot-z-norm");
-  PropertyManager->Untie("position/epa-rad");
-  /* PropertyManager->Untie("atmosphere/headwind-fps");
-  PropertyManager->Untie("atmosphere/crosswind-fps"); */
-  PropertyManager->Untie("aero/qbar-psf");
-  PropertyManager->Untie("aero/qbarUW-psf");
-  PropertyManager->Untie("aero/qbarUV-psf");
-  PropertyManager->Untie("aero/alpha-rad");
-  PropertyManager->Untie("aero/beta-rad");
-  PropertyManager->Untie("aero/alpha-deg");
-  PropertyManager->Untie("aero/beta-deg");
-  PropertyManager->Untie("aero/alphadot-rad_sec");
-  PropertyManager->Untie("aero/betadot-rad_sec");
-  PropertyManager->Untie("aero/mag-beta-rad");
-  PropertyManager->Untie("aero/alphadot-deg_sec");
-  PropertyManager->Untie("aero/betadot-deg_sec");
-  PropertyManager->Untie("aero/mag-beta-deg");
-  PropertyManager->Untie("aero/h_b-cg-ft");
-  PropertyManager->Untie("aero/h_b-mac-ft");
-  PropertyManager->Untie("flight-path/gamma-rad");
-  PropertyManager->Untie("flight-path/psi-gt-rad");
-}
+void FGAuxiliary::CalculateRelativePosition(void)
+{ 
+  const double earth_radius_mt = Inertial->GetRefRadius()*fttom;
+  lat_relative_position=(FDMExec->GetPropagate()->GetLatitude()  - FDMExec->GetIC()->GetLatitudeDegIC() *degtorad)*earth_radius_mt;
+  lon_relative_position=(FDMExec->GetPropagate()->GetLongitude() - FDMExec->GetIC()->GetLongitudeDegIC()*degtorad)*earth_radius_mt;
+  relative_position = sqrt(lat_relative_position*lat_relative_position + lon_relative_position*lon_relative_position);
+};
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
index 0428ff9eb60f51a9d938cafdc770f69b00e44fef..e551f5e3dd319ce85754f9eaddc48300555c0405 100644 (file)
@@ -116,6 +116,8 @@ public:
   /// Destructor
   ~FGAuxiliary();
 
+  bool InitModel(void);
+
   /** Runs the Auxiliary routines; called by the Executive
       @return false if no error */
   bool Run(void);
@@ -123,14 +125,28 @@ public:
 // GET functions
 
   // Atmospheric parameters GET functions
+  /** Returns Calibrated airspeed in feet/second.*/
   double GetVcalibratedFPS(void) const { return vcas; }
+  /** Returns Calibrated airspeed in knots.*/
   double GetVcalibratedKTS(void) const { return vcas*fpstokts; }
+  /** Returns equivalent airspeed in feet/second. */
   double GetVequivalentFPS(void) const { return veas; }
+  /** Returns equivalent airspeed in knots. */
   double GetVequivalentKTS(void) const { return veas*fpstokts; }
 
-  // total pressure above is freestream total pressure for subsonic only
-  // for supersonic it is the 1D total pressure behind a normal shock
+  /** Returns the total pressure.
+      Total pressure is freestream total pressure for
+      subsonic only. For supersonic it is the 1D total pressure
+      behind a normal shock. */
   double GetTotalPressure(void) const { return pt; }
+
+  /** Returns the total temperature.
+    The total temperature ("tat", isentropic flow) is calculated:
+    @code
+    tat = sat*(1 + 0.2*Mach*Mach)
+    @endcode
+    (where "sat" is standard temperature) */
+
   double GetTotalTemperature(void) const { return tat; }
   double GetTAT_C(void) const { return tatc; }
 
@@ -172,16 +188,16 @@ public:
   double GetVground (void) const { return Vground;    }
   double GetMach    (void) const { return Mach;       }
   double GetMachU   (void) const { return MachU;      }
+  double GetNz      (void) const { return Nz;         }
 
   double GetHOverBCG(void) const { return hoverbcg; }
   double GetHOverBMAC(void) const { return hoverbmac; }
 
   double GetGamma(void)              const { return gamma;         }
   double GetGroundTrack(void)        const { return psigt;         }
-  double GetEarthPositionAngle(void) const { return earthPosAngle; }
 
-  double GetHeadWind(void);
-  double GetCrossWind(void);
+  double GetHeadWind(void) const;
+  double GetCrossWind(void) const;
 
 // SET functions
 
@@ -200,7 +216,7 @@ public:
   void SetAB    (double t1, double t2) { alpha=t1; beta=t2; }
   void SetGamma (double tt)            { gamma = tt;        }
 
-// Time routines, SET and GET functions
+// Time routines, SET and GET functions, used by FGMSIS atmosphere
 
   void SetDayOfYear    (int doy)    { day_of_year = doy;    }
   void SetSecondsInDay (double sid) { seconds_in_day = sid; }
@@ -208,8 +224,11 @@ public:
   int    GetDayOfYear    (void) const { return day_of_year;    }
   double GetSecondsInDay (void) const { return seconds_in_day; }
 
-  void bind(void);
-  void unbind(void);
+  double GetLongitudeRelativePosition (void) const { return lon_relative_position; }
+  double GetLatitudeRelativePosition  (void) const { return lat_relative_position; }
+  double GetDistanceRelativePosition  (void) const { return relative_position; }
+
+  void SetAeroPQR(FGColumnVector3 tt) { vAeroPQR = tt; }
 
 private:
   double vcas, veas;
@@ -223,6 +242,7 @@ private:
   FGColumnVector3 vEuler;
   FGColumnVector3 vEulerRates;
   FGColumnVector3 vMachUVW;
+  FGColumnVector3 vAircraftAccel;
   FGLocation vLocationVRP;
 
   double Vt, Vground, Mach, MachU;
@@ -230,12 +250,21 @@ private:
   double alpha, beta;
   double adot,bdot;
   double psigt, gamma;
+  double Nz;
   double seconds_in_day;  // seconds since current GMT day began
   int    day_of_year;     // GMT day, 1 .. 366
 
-  double earthPosAngle;
   double hoverbcg, hoverbmac;
 
+  // helper data, calculation of distance from initial position
+
+  double lon_relative_position;
+  double lat_relative_position;
+  double relative_position;
+
+  void CalculateRelativePosition(void);
+
+  void bind(void);
   void Debug(int from);
 };
 
diff --git a/src/FDM/JSBSim/models/FGBuoyantForces.cpp b/src/FDM/JSBSim/models/FGBuoyantForces.cpp
new file mode 100644 (file)
index 0000000..505c803
--- /dev/null
@@ -0,0 +1,309 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Module:       FGBuoyantForces.cpp
+ Authors:      Anders Gidenstam, Jon S. Berndt
+ Date started: 01/21/08
+ Purpose:      Encapsulates the buoyant forces
+
+ ------------- Copyright (C) 2008  Anders Gidenstam               -------------
+ ------------- Copyright (C) 2008  Jon S. Berndt (jsb@hal-pc.org) -------------
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+FUNCTIONAL DESCRIPTION
+--------------------------------------------------------------------------------
+
+HISTORY
+--------------------------------------------------------------------------------
+01/21/08   JSB   Created
+
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#include "FGBuoyantForces.h"
+#include "FGMassBalance.h"
+#include <input_output/FGPropertyManager.h>  // Need?
+
+namespace JSBSim {
+
+static const char *IdSrc = "$Id$";
+static const char *IdHdr = ID_BUOYANTFORCES;
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS IMPLEMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+FGBuoyantForces::FGBuoyantForces(FGFDMExec* FDMExec) : FGModel(FDMExec)
+{
+  Name = "FGBuoyantForces";
+
+  NoneDefined = true;
+
+  vTotalForces.InitMatrix();
+  vTotalMoments.InitMatrix();
+
+  gasCellJ.InitMatrix();
+
+  bind();
+
+  Debug(0);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGBuoyantForces::~FGBuoyantForces()
+{
+  for (unsigned int i=0; i<Cells.size(); i++) delete Cells[i];
+  Cells.clear();
+
+  unbind();
+
+  Debug(1);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGBuoyantForces::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGBuoyantForces::Run(void)
+{
+  if (FGModel::Run()) return true;
+  if (FDMExec->Holding()) return false; // if paused don't execute
+  if (NoneDefined) return true;
+
+  vTotalForces.InitMatrix();
+  vTotalMoments.InitMatrix();
+
+  for (unsigned int i=0; i<Cells.size(); i++) {
+    Cells[i]->Calculate(FDMExec->GetDeltaT());
+    vTotalForces  += Cells[i]->GetBodyForces();
+    vTotalMoments += Cells[i]->GetMoments();
+  }
+
+  return false;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGBuoyantForces::Load(Element *element)
+{
+  string fname="", file="";
+  Element *gas_cell_element;
+
+  Debug(2);
+
+  string separator = "/";
+#ifdef macintosh
+  separator = ";";
+#endif
+
+  fname = element->GetAttributeValue("file");
+  if (!fname.empty()) {
+    file = FDMExec->GetFullAircraftPath() + separator + fname;
+    document = LoadXMLDocument(file);
+  } else {
+    document = element;
+  }
+
+  gas_cell_element = document->FindElement("gas_cell");
+  while (gas_cell_element) {
+    NoneDefined = false;
+    Cells.push_back(new FGGasCell(FDMExec, gas_cell_element, Cells.size()));
+    gas_cell_element = document->FindNextElement("gas_cell");
+  }
+  
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+double FGBuoyantForces::GetGasMass(void)
+{
+  double Gw = 0.0;
+
+  for (unsigned int i = 0; i < Cells.size(); i++) {
+    Gw += Cells[i]->GetMass();
+  }
+
+  return Gw;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGColumnVector3& FGBuoyantForces::GetGasMassMoment(void)
+{
+  vXYZgasCell_arm.InitMatrix();
+  for (unsigned int i = 0; i < Cells.size(); i++) {
+    vXYZgasCell_arm += Cells[i]->GetMassMoment();
+  }
+  return vXYZgasCell_arm;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGMatrix33& FGBuoyantForces::GetGasMassInertia(void)
+{
+  const unsigned int size = Cells.size();
+  
+  if (size == 0) return gasCellJ;
+
+  gasCellJ = FGMatrix33();
+
+  for (unsigned int i=0; i < size; i++) {
+    FGColumnVector3 v = MassBalance->StructuralToBody( Cells[i]->GetXYZ() );
+    // Body basis is in FT. 
+    const double mass = Cells[i]->GetMass();
+    
+    // FIXME: Verify that this is the correct way to change between the
+    //        coordinate frames.
+    gasCellJ += Cells[i]->GetInertia() + 
+      FGMatrix33( 0,                - mass*v(1)*v(2), - mass*v(1)*v(3),
+                  - mass*v(2)*v(1), 0,                - mass*v(2)*v(3),
+                  - mass*v(3)*v(1), - mass*v(3)*v(2), 0 );
+  }
+  
+  return gasCellJ;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+string FGBuoyantForces::GetBuoyancyStrings(string delimeter)
+{
+  string CoeffStrings = "";
+  bool firstime = true;
+/*
+  for (sd = 0; sd < variables.size(); sd++) {
+    if (firstime) {
+      firstime = false;
+    } else {
+      CoeffStrings += delimeter;
+    }
+    CoeffStrings += variables[sd]->GetName();
+  }
+
+  for (axis = 0; axis < 6; axis++) {
+    for (sd = 0; sd < Coeff[axis].size(); sd++) {
+      if (firstime) {
+        firstime = false;
+      } else {
+        CoeffStrings += delimeter;
+      }
+      CoeffStrings += Coeff[axis][sd]->GetName();
+    }
+  }
+*/
+  return CoeffStrings;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+string FGBuoyantForces::GetBuoyancyValues(string delimeter)
+{
+  string SDValues = "";
+  bool firstime = true;
+/*
+  for (sd = 0; sd < variables.size(); sd++) {
+    if (firstime) {
+      firstime = false;
+    } else {
+      SDValues += delimeter;
+    }
+    SDValues += variables[sd]->GetValueAsString();
+  }
+
+  for (unsigned int axis = 0; axis < 6; axis++) {
+    for (unsigned int sd = 0; sd < Coeff[axis].size(); sd++) {
+      if (firstime) {
+        firstime = false;
+      } else {
+        SDValues += delimeter;
+      }
+      SDValues += Coeff[axis][sd]->GetValueAsString();
+    }
+  }
+*/
+  return SDValues;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGBuoyantForces::bind(void)
+{
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGBuoyantForces::unbind(void)
+{
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//    The bitmasked value choices are as follows:
+//    unset: In this case (the default) JSBSim would only print
+//       out the normally expected messages, essentially echoing
+//       the config files as they are read. If the environment
+//       variable is not set, debug_lvl is set to 1 internally
+//    0: This requests JSBSim not to output any messages
+//       whatsoever.
+//    1: This value explicity requests the normal JSBSim
+//       startup messages
+//    2: This value asks for a message to be printed out when
+//       a class is instantiated
+//    4: When this value is set, a message is displayed when a
+//       FGModel object executes its Run() method
+//    8: When this value is set, various runtime state variables
+//       are printed out periodically
+//    16: When set various parameters are sanity checked and
+//       a message is printed out when they go out of bounds
+
+void FGBuoyantForces::Debug(int from)
+{
+  if (debug_lvl <= 0) return;
+
+  if (debug_lvl & 1) { // Standard console startup message output
+    if (from == 2) { // Loader
+      cout << endl << "  Buoyant Forces: " << endl;
+    }
+  }
+  if (debug_lvl & 2 ) { // Instantiation/Destruction notification
+    if (from == 0) cout << "Instantiated: FGBuoyantForces" << endl;
+    if (from == 1) cout << "Destroyed:    FGBuoyantForces" << endl;
+  }
+  if (debug_lvl & 4 ) { // Run() method entry print for FGModel-derived objects
+  }
+  if (debug_lvl & 8 ) { // Runtime state variables
+  }
+  if (debug_lvl & 16) { // Sanity checking
+  }
+  if (debug_lvl & 64) {
+    if (from == 0) { // Constructor
+      cout << IdSrc << endl;
+      cout << IdHdr << endl;
+    }
+  }
+}
+
+} // namespace JSBSim
diff --git a/src/FDM/JSBSim/models/FGBuoyantForces.h b/src/FDM/JSBSim/models/FGBuoyantForces.h
new file mode 100644 (file)
index 0000000..86f5d69
--- /dev/null
@@ -0,0 +1,191 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Header:       FGBuoyantForces.h
+ Author:       Anders Gidenstam, Jon S. Berndt
+ Date started: 01/21/08
+
+ ------------- Copyright (C) 2008  Anders Gidenstam               -------------
+ ------------- Copyright (C) 2008  Jon S. Berndt (jsb@hal-pc.org) -------------
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+HISTORY
+--------------------------------------------------------------------------------
+01/21/08   JSB   Created
+
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+SENTRY
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#ifndef FGBuoyanTFORCES_H
+#define FGBuoyanTFORCES_H
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#ifdef FGFS
+#  include <simgear/compiler.h>
+#  ifdef SG_HAVE_STD_INCLUDES
+#    include <vector>
+#    include <map>
+#  else
+#    include <vector.h>
+#    include <map.h>
+#  endif
+#else
+#  include <vector>
+#  include <map>
+#endif
+
+#include "FGModel.h"
+#include "FGGasCell.h"
+#include <math/FGColumnVector3.h>
+#include <input_output/FGXMLFileRead.h>
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+DEFINITIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#define ID_BUOYANTFORCES "$Id$"
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+FORWARD DECLARATIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+namespace JSBSim {
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DOCUMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+/** Encapsulates the Buoyant forces calculations.
+    This class owns and contains the list of force/coefficients that define the
+    Buoyant properties of an air vehicle.
+    
+    Here's an example of a gas cell specification:
+
+    @code
+    <buoyant_forces>
+      <gas_cell type="HYDROGEN">
+        <location unit="M">
+          <x> 18.8 </x>
+          <y> 0.0 </y>
+          <z> 0.0 </z>
+        </location>
+        <x_radius unit="M"> 22.86 </x_radius>
+        <y_radius unit="M">  4.55 </y_radius>
+        <z_radius unit="M">  4.55 </z_radius>
+        <max_overpressure unit="PA"> 340.0 </max_overpressure> 
+        <valve_coefficient unit="M4*SEC/KG"> 0.015 </valve_coefficient>
+      </gas_cell>
+      
+      ... {other gass cells} ...
+      
+    </buoyant_forces>
+    @endcode
+
+    See FGGasCell for the full configuration file format for gas cells.
+
+    @author Anders Gidenstam, Jon S. Berndt
+    @version $Id$
+*/
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DECLARATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+class FGBuoyantForces : public FGModel, public FGXMLFileRead
+{
+
+public:
+  /** Constructor
+      @param Executive a pointer to the parent executive object */
+  FGBuoyantForces(FGFDMExec* Executive);
+  /// Destructor
+  ~FGBuoyantForces();
+
+  bool InitModel(void);
+
+  /** Runs the Buoyant forces model; called by the Executive
+      @return false if no error */
+  bool Run(void);
+
+  /** Loads the Buoyant forces model.
+      The Load function for this class expects the XML parser to
+      have found the Buoyant_forces keyword in the configuration file.
+      @param element pointer to the current XML element for Buoyant forces parameters.
+      @return true if successful */
+  bool Load(Element* element);
+
+  /** Gets the total Buoyant force vector.
+      @return a force vector. */
+  FGColumnVector3 GetForces(void) {return vTotalForces;}
+
+  /** Gets the total Buoyancy moment vector.
+      @return a moment vector. */
+  FGColumnVector3 GetMoments(void) {return vTotalMoments;}
+
+  /** Gets the total gas mass. The gas mass is part of the aircraft's
+      inertia.
+      @return mass in slugs. */
+  double GetGasMass(void);
+
+  /** Gets the total moment from the gas mass.
+      @return a moment vector. */
+  FGColumnVector3& GetGasMassMoment(void);
+
+  /** Gets the total moments of inertia for the gas mass.
+      @return . */
+  FGMatrix33& GetGasMassInertia(void);
+
+  /** Gets the strings for the current set of gas cells.
+      @param delimeter either a tab or comma string depending on output type
+      @return a string containing the descriptive names for all parameters */
+  string GetBuoyancyStrings(string delimeter);
+
+  /** Gets the coefficient values.
+      @param delimeter either a tab or comma string depending on output type
+      @return a string containing the numeric values for the current set of
+      parameters */
+  string GetBuoyancyValues(string delimeter);
+
+private:
+  vector <FGGasCell*> Cells;
+  // Buoyant forces and moments. Excluding the gas weight.
+  FGColumnVector3 vTotalForces;
+  FGColumnVector3 vTotalMoments;
+
+  // Gas mass related masses, inertias and moments.
+  FGMatrix33 gasCellJ;
+  FGColumnVector3 vGasCellXYZ;
+  FGColumnVector3 vXYZgasCell_arm;
+
+  bool NoneDefined;
+
+  void bind(void);
+  void unbind(void);
+
+  void Debug(int from);
+};
+
+} // namespace JSBSim
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+#endif
+
diff --git a/src/FDM/JSBSim/models/FGExternalForce.cpp b/src/FDM/JSBSim/models/FGExternalForce.cpp
new file mode 100755 (executable)
index 0000000..a9e13c9
--- /dev/null
@@ -0,0 +1,238 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Source:       FGExternalForce.cpp
+ Author:       Jon Berndt, Dave Culp
+ Date started: 9/21/07
+
+ ------------- Copyright (C) 2007  Jon S. Berndt (jsb@hal-pc.org) -------------
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+ HISTORY
+--------------------------------------------------------------------------------
+9/21/07  JB   Created
+
+<external_reactions>
+
+    <!-- Interface properties, a.k.a. property declarations -->
+    <property> ... </property>
+      
+    <force name="name" frame="BODY|LOCAL|WIND">
+      
+      <function> ... </function>
+
+      <location unit="units"> <!-- location -->
+        <x> value </x>
+        <y> value </y>
+        <z> value </z>
+      </location>
+      <direction> <!-- optional for initial direction vector -->
+        <x> value </x>
+        <y> value </y>
+        <z> value </z>
+      </direction>
+    </force>
+
+</external_reactions>
+
+*/
+
+#include "FGExternalForce.h"
+
+namespace JSBSim {
+
+static const char *IdSrc = "$Id$";
+static const char *IdHdr = ID_EXTERNALFORCE;
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGExternalForce::FGExternalForce(FGFDMExec *FDMExec, Element *el, int index): FGForce(FDMExec)
+{
+  Element* location_element=0;
+  Element* direction_element=0;
+  Element* function_element=0;
+  string sFrame;
+  string BasePropertyName;
+  FGColumnVector3 location;
+  Magnitude_Function = 0;
+  magnitude = 0.0;
+  azimuth = 0.0;
+
+  PropertyManager = fdmex->GetPropertyManager();
+  Name = el->GetAttributeValue("name");
+  BasePropertyName = "external_reactions/" + Name;
+
+  // The value sent to the sim through the external_forces/{force name}/magnitude
+  // property will be multiplied against the unit vector, which can come in
+  // initially in the direction vector. The frame in which the vector is defined
+  // is specified with the frame attribute. The vector is normalized to magnitude 1.
+
+  function_element = el->FindElement("function");
+  if (function_element) {
+    Magnitude_Function = new FGFunction(PropertyManager, function_element);
+  } else {
+    PropertyManager->Tie( BasePropertyName + "/magnitude",(FGExternalForce*)this, &FGExternalForce::GetMagnitude, &FGExternalForce::SetMagnitude);
+    Magnitude_Node = PropertyManager->GetNode(BasePropertyName + "/magnitude");
+  }
+
+
+  // Set frame (from FGForce).
+  sFrame = el->GetAttributeValue("frame");
+  if (sFrame.empty()) {
+    cerr << "No frame specified for external force, \"" << Name << "\"." << endl;
+    cerr << "Frame set to Body" << endl;
+    ttype = tNone;
+  } else if (sFrame == "BODY") {
+    ttype = tNone;
+  } else if (sFrame == "LOCAL") {
+    ttype = tLocalBody;
+    PropertyManager->Tie( BasePropertyName + "/azimuth", (FGExternalForce*)this, &FGExternalForce::GetAzimuth, &FGExternalForce::SetAzimuth);
+  } else if (sFrame == "WIND") {
+    ttype = tWindBody;
+  } else {
+    cerr << "Invalid frame specified for external force, \"" << Name << "\"." << endl;
+    cerr << "Frame set to Body" << endl;
+    ttype = tNone;
+  }
+  PropertyManager->Tie( BasePropertyName + "/x", (FGExternalForce*)this, &FGExternalForce::GetX, &FGExternalForce::SetX);
+  PropertyManager->Tie( BasePropertyName + "/y", (FGExternalForce*)this, &FGExternalForce::GetY, &FGExternalForce::SetY);
+  PropertyManager->Tie( BasePropertyName + "/z", (FGExternalForce*)this, &FGExternalForce::GetZ, &FGExternalForce::SetZ);
+
+  location_element = el->FindElement("location");
+  if (!location_element) {
+    cerr << "No location element specified in force object." << endl;
+  } else {
+    location = location_element->FindElementTripletConvertTo("IN");
+    SetLocation(location);
+  }
+
+  direction_element = el->FindElement("direction");
+  if (!direction_element) {
+    cerr << "No direction element specified in force object. Default is (0,0,0)." << endl;
+  } else {
+    vDirection = direction_element->FindElementTripletConvertTo("IN");
+    vDirection.Normalize();
+  }
+
+  Debug(0);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+// Copy constructor
+
+FGExternalForce::FGExternalForce(const FGExternalForce& extForce) : FGForce(extForce)
+{
+  magnitude = extForce.magnitude;
+  Frame = extForce.Frame;
+  vDirection = extForce.vDirection;
+  Name = extForce.Name;
+  BasePropertyName = extForce.BasePropertyName;
+  PropertyManager = extForce.PropertyManager;
+}
+  
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGExternalForce::~FGExternalForce()
+{
+  unbind( PropertyManager->GetNode("external_reactions"));
+
+  Debug(1);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGExternalForce::SetMagnitude(double mag)
+{
+  magnitude = mag;
+  vFn = vDirection*mag;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGColumnVector3& FGExternalForce::GetBodyForces(void)
+{
+  if (Magnitude_Function) {
+    double mag = Magnitude_Function->GetValue();
+    SetMagnitude(mag);
+  }
+  
+  return FGForce::GetBodyForces();
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGExternalForce::unbind(FGPropertyManager *node)
+{
+  int N = node->nChildren();
+  for (int i=0; i<N; i++) {
+    if (node->getChild(i)->nChildren() ) {
+      unbind( (FGPropertyManager*)node->getChild(i) );
+    } else if ( node->getChild(i)->isTied() ) {
+      node->getChild(i)->untie();
+    }
+  }
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//    The bitmasked value choices are as follows:
+//    unset: In this case (the default) JSBSim would only print
+//       out the normally expected messages, essentially echoing
+//       the config files as they are read. If the environment
+//       variable is not set, debug_lvl is set to 1 internally
+//    0: This requests JSBSim not to output any messages
+//       whatsoever.
+//    1: This value explicity requests the normal JSBSim
+//       startup messages
+//    2: This value asks for a message to be printed out when
+//       a class is instantiated
+//    4: When this value is set, a message is displayed when a
+//       FGModel object executes its Run() method
+//    8: When this value is set, various runtime state variables
+//       are printed out periodically
+//    16: When set various parameters are sanity checked and
+//       a message is printed out when they go out of bounds
+
+void FGExternalForce::Debug(int from)
+{
+  if (debug_lvl <= 0) return;
+
+  if (debug_lvl & 1) { // Standard console startup message output
+    if (from == 0) { // Constructor
+      cout << "    " << Name << endl;
+      cout << "    Frame: " << Frame << endl;
+      cout << "    Location: (" << vXYZn(eX) << ", " << vXYZn(eY) << ", " << vXYZn(eZ) << ")" << endl;
+    }
+  }
+  if (debug_lvl & 2 ) { // Instantiation/Destruction notification
+    if (from == 0) cout << "Instantiated: FGExternalForce" << endl;
+    if (from == 1) cout << "Destroyed:    FGExternalForce" << endl;
+  }
+  if (debug_lvl & 4 ) { // Run() method entry print for FGModel-derived objects
+  }
+  if (debug_lvl & 8 ) { // Runtime state variables
+  }
+  if (debug_lvl & 16) { // Sanity checking
+  }
+  if (debug_lvl & 64) {
+    if (from == 0) { // Constructor
+      cout << IdSrc << endl;
+      cout << IdHdr << endl;
+    }
+  }
+}
+}
diff --git a/src/FDM/JSBSim/models/FGExternalForce.h b/src/FDM/JSBSim/models/FGExternalForce.h
new file mode 100755 (executable)
index 0000000..3ba6641
--- /dev/null
@@ -0,0 +1,183 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Header:       FGExternalForce.h
+ Author:       Jon Berndt, Dave Culp
+ Date started: 9/21/07
+
+ ------------- Copyright (C) 2007  Jon S. Berndt (jsb@hal-pc.org) -------------
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+
+ HISTORY
+--------------------------------------------------------------------------------
+9/21/07  JB   Created
+
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+SENTRY
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#ifndef FGEXTERNALFORCE_H
+#define FGEXTERNALFORCE_H
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#include <FGFDMExec.h>
+#include <FGJSBBase.h>
+#include <models/propulsion/FGForce.h>
+#include <string>
+#include <input_output/FGPropertyManager.h>
+#include <math/FGColumnVector3.h>
+#include <math/FGFunction.h>
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+DEFINITIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#define ID_EXTERNALFORCE "$Id$"
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+FORWARD DECLARATIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+namespace JSBSim {
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DOCUMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+/** Encapsulates code that models an individual arbitrary force.
+    This class encapsulates an individual force applied at the specified
+    location on the vehicle, and oriented as specified in one of three frames:
+    
+    - BODY frame is defined with the X axis positive forward, the Y axis
+           positive out the right wing, and the Z axis completing the set
+           positive downward out the belly of the aircraft.
+    - LOCAL frame is a world-based frame, with X positive north, Y positive east
+            and Z completing the right handed system positive down towards
+            the center of the Earth.
+    - WIND frame (rotated) has X negative into the wind vector (in other words
+           drag is along the positive X axis), the Z axis is perpendicular to
+           X and positive up (lift) but in the aircraft XZ plane, and Y
+           completes the right handed system. This is modified from a normal
+           wind frame definition, which is rotated about the Y axis 180 degrees
+           from this WIND frame.
+
+    Much of the substance of this class is located in the FGForce base class, from
+    which this class is derived.
+    
+    Here is the XML definition of a force (optional items are in []):
+    
+    @code
+    <force name="name" frame="BODY | LOCAL | WIND">
+      
+      [<function> ... </function>]
+
+      <location unit="{IN | M}"> 
+        <x> {number} </x>
+        <y> {number} </y>
+        <z> {number} </z>
+      </location>
+      [<direction> <!-- optional initial direction vector -->
+        <x> {number} </x>
+        <y> {number} </y>
+        <z> {number} </z>
+      </direction>]
+    </force>
+    @endcode
+
+    The initial direction can optionally be set by specifying a unit vector
+    in the chosen frame (body, local, or wind). The direction is specified
+    at runtime through setting any/all of the following properties:
+    
+    @code
+    external_reactions/{force name}/x
+    external_reactions/{force name}/y
+    external_reactions/{force name}/z
+    @endcode
+    
+    As an example, a parachute can be defined oriented in the wind axis frame
+    so the drag always acts in the drag direction - opposite the positive X
+    axis. That does not include the effects of parachute oscillations, but
+    those could be handled in the calling application.
+     
+    The force direction is not actually required to be specified as a unit
+    vector, but prior to the force vector being calculated, the direction
+    vector is normalized.
+    
+*/
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DECLARATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+class FGExternalForce : public FGForce
+{
+public:
+  /** Constructor.
+      @param FDMExec pointer to the main executive class.
+  */
+  FGExternalForce(FGFDMExec *FDMExec);
+
+  /** Constructor.
+      @param FDMExec pointer to the main executive class.
+      @param el pointer to the XML element defining an individual force.
+      @param index the position of this force object in the whole list.
+  */
+  FGExternalForce(FGFDMExec *FDMExec, Element *el, int index);
+
+  /** Copy Constructor
+      @param extForce a reference to an existing FGExternalForce object
+  */
+  FGExternalForce(const FGExternalForce& extForce);
+
+  /// Destructor
+  ~FGExternalForce();
+
+  void SetMagnitude(double mag);
+  void SetAzimuth(double az) {azimuth = az;}
+
+  FGColumnVector3& GetBodyForces(void);
+  double GetMagnitude(void) const {return magnitude;}
+  double GetAzimuth(void) const {return azimuth;}
+  double GetX(void) const {return vDirection(eX);}
+  double GetY(void) const {return vDirection(eY);}
+  double GetZ(void) const {return vDirection(eZ);}
+  void SetX(double x) {vDirection(eX) = x;}
+  void SetY(double y) {vDirection(eY) = y;}
+  void SetZ(double z) {vDirection(eZ) = z;}
+  
+private:
+
+  string Frame;
+  string Name;
+  FGPropertyManager* PropertyManager;
+  FGPropertyManager* Magnitude_Node;
+  FGFunction* Magnitude_Function;
+  string BasePropertyName;
+  FGColumnVector3 vDirection;
+  double magnitude;
+  double azimuth;
+  void unbind(FGPropertyManager *node);
+  void Debug(int from);
+};
+}
+#endif
+
diff --git a/src/FDM/JSBSim/models/FGExternalReactions.cpp b/src/FDM/JSBSim/models/FGExternalReactions.cpp
new file mode 100755 (executable)
index 0000000..0add9cf
--- /dev/null
@@ -0,0 +1,192 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Module:       FGExternalReactions.cpp
+ Author:       David P. Culp
+ Date started: 17/11/06
+ Purpose:      Manages the External Forces
+ Called by:    FGAircraft
+
+ ------------- Copyright (C) 2006  David P. Culp (davidculp2@comcast.net) -------------
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+FUNCTIONAL DESCRIPTION
+--------------------------------------------------------------------------------
+
+HISTORY
+--------------------------------------------------------------------------------
+17/11/06   DC   Created
+
+/%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#include "FGExternalReactions.h"
+#include <string>
+
+namespace JSBSim {
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+DEFINITIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+GLOBAL DATA
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+static const char *IdSrc = "$Id$";
+static const char *IdHdr = ID_EXTERNALREACTIONS;
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS IMPLEMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+FGExternalReactions::FGExternalReactions(FGFDMExec* fdmex) : FGModel(fdmex)
+{
+  NoneDefined = true;
+  Debug(0);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGExternalReactions::Load(Element* el)
+{
+  Debug(2);
+
+  // Interface properties are all stored in the interface properties array.
+  // ToDo: Interface properties should not be created if they already exist.
+  // A check should be done prior to creation. This ought to make it easier 
+  // to work with FlightGear, where some properties used in definitions may 
+  // already have been created, but would not be seen when JSBSim is run
+  // in standalone mode.
+
+  Element* property_element;
+  property_element = el->FindElement("property");
+  while (property_element) {
+    double value=0.0;
+    if ( ! property_element->GetAttributeValue("value").empty())
+      value = property_element->GetAttributeValueAsNumber("value");
+    interface_properties.push_back(new double(value));
+    string interface_property_string = property_element->GetDataLine();
+    PropertyManager->Tie(interface_property_string, interface_properties.back());
+    property_element = el->FindNextElement("property");
+  }
+
+  // Parse force elements
+
+  int index=0;
+  Element* force_element = el->FindElement("force");
+  while (force_element) {
+    Forces.push_back( new FGExternalForce(FDMExec, force_element, index) );
+    NoneDefined = false;
+    index++; 
+    force_element = el->FindNextElement("force");
+  }
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGExternalReactions::~FGExternalReactions()
+{
+  for (unsigned int i=0; i<Forces.size(); i++) delete Forces[i];
+  Forces.clear();
+  for (unsigned int i=0; i<interface_properties.size(); i++) delete interface_properties[i];
+  interface_properties.clear();
+  Debug(1);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGExternalReactions::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGExternalReactions::Run()
+{
+  if (FGModel::Run()) return true;
+  if (FDMExec->Holding()) return false; // if paused don't execute
+  if (NoneDefined) return true;
+
+  vTotalForces.InitMatrix();
+  vTotalMoments.InitMatrix();
+
+  for (unsigned int i=0; i<Forces.size(); i++) {
+    vTotalForces  += Forces[i]->GetBodyForces();
+    vTotalMoments += Forces[i]->GetMoments();
+  }
+
+  return false;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//    The bitmasked value choices are as follows:
+//    unset: In this case (the default) JSBSim would only print
+//       out the normally expected messages, essentially echoing
+//       the config files as they are read. If the environment
+//       variable is not set, debug_lvl is set to 1 internally
+//    0: This requests JSBSim not to output any messages
+//       whatsoever.
+//    1: This value explicity requests the normal JSBSim
+//       startup messages
+//    2: This value asks for a message to be printed out when
+//       a class is instantiated
+//    4: When this value is set, a message is displayed when a
+//       FGModel object executes its Run() method
+//    8: When this value is set, various runtime state variables
+//       are printed out periodically
+//    16: When set various parameters are sanity checked and
+//       a message is printed out when they go out of bounds
+
+void FGExternalReactions::Debug(int from)
+{
+  if (debug_lvl <= 0) return;
+
+  if (debug_lvl & 1) { // Standard console startup message output
+    if (from == 0) { // Constructor - loading and initialization
+    }
+    if (from == 2) { // Loading
+      cout << endl << "  External Reactions: " << endl;
+    }
+  }
+  if (debug_lvl & 2 ) { // Instantiation/Destruction notification
+    if (from == 0) cout << "Instantiated: FGExternalReactions" << endl;
+    if (from == 1) cout << "Destroyed:    FGExternalReactions" << endl;
+  }
+  if (debug_lvl & 4 ) { // Run() method entry print for FGModel-derived objects
+  }
+  if (debug_lvl & 8 ) { // Runtime state variables
+  }
+  if (debug_lvl & 16) { // Sanity checking
+  }
+  if (debug_lvl & 64) {
+    if (from == 0) { // Constructor
+      cout << IdSrc << endl;
+      cout << IdHdr << endl;
+    }
+  }
+}
+
+} // namespace JSBSim
+
diff --git a/src/FDM/JSBSim/models/FGExternalReactions.h b/src/FDM/JSBSim/models/FGExternalReactions.h
new file mode 100755 (executable)
index 0000000..16db9c7
--- /dev/null
@@ -0,0 +1,174 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Header:       FGExternalReactions.h
+ Author:       David P. Culp
+ Date started: 17/11/06
+
+ ------------- Copyright (C) 2006  David P. Culp (davidculp2@comcast.net) -------------
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+HISTORY
+--------------------------------------------------------------------------------
+17/11/06   DPC   Created
+
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+SENTRY
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#ifndef FGEXTERNALREACTIONS_H
+#define FGEXTERNALREACTIONS_H
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#ifdef FGFS
+#  include <simgear/compiler.h>
+#endif
+
+#include "FGModel.h"
+#include "FGExternalForce.h"
+#include <input_output/FGXMLElement.h>
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+DEFINITIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#define ID_EXTERNALREACTIONS "$Id$"
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+FORWARD DECLARATIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+namespace JSBSim {
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DOCUMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+/** Manages the external and/or arbitrary forces.
+    The external reactions capability in JSBSim really should be named
+    "arbitrary forces", because this feature can be used to model a wide
+    variety of forces that act on a vehicle. Some examples include: parachutes,
+    catapult, arresting hook, and tow line.
+    
+    This class acts similarly to the other "manager classes" (FGPropulsion, 
+    FGFCS, FGGroundReactions, FGAerodynamics) because it manages collections
+    of constituent forces. The individual forces are implemented with the
+    FGExternalForce class.
+    
+    The format of the <em>optional</em> external reactions section in the config
+    file is as follows:
+    
+    @code
+<external_reactions>
+
+  <!-- Interface properties, a.k.a. property declarations -->
+  <property> ... </property>
+    
+  <force name="name" frame="BODY | LOCAL | WIND" unit="unit">
+    ...
+  </force>
+
+  <!-- Additional force definitions may follow -->
+  <force name="name" frame="BODY | LOCAL | WIND" unit="unit">
+    ...
+  </force>
+
+</external_reactions>
+    @endcode
+
+    See the FGExternalForce class for more information on the format of the
+    force specification itself.
+    
+    When force elements are encountered in the configuration file, a new instance
+    of the FGExternalForce class is created and a pointer to the class is pushed
+    onto the Forces vector.
+    
+    This class is one of a few of the manager classes that allows properties
+    to be "declared". In code, these are represented by the
+    <em>interface_properties</em> vector. Properties that have not yet been
+    created in an already parsed section of the configuration file and that are
+    used in the definition of an external force should be declared in the
+    external_reactions section because they will not be created automatically,
+    and so would cause an error, since the property cannot be found to exist.
+        
+    See the FGExternalForce documentation for details on how forces are
+    actually calculated.
+  */
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DECLARATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+class FGExternalReactions : public FGModel
+{
+public:
+  /** Constructor.
+      @param fdmex pointer to the main executive class.
+  */
+  FGExternalReactions(FGFDMExec* fdmex);
+  
+  /** Destructor.
+      Within the destructor the Forces and interface_properties vectors are
+      cleared out and the items pointed to are deleted.
+  */
+  ~FGExternalReactions(void);
+
+  bool InitModel(void);
+
+  /** Sum all the constituent forces for this cycle.
+      @return true always.
+  */
+  bool Run(void);
+  
+  /** Loads the external forces from the XML configuration file.
+      If the external_reactions section is encountered in the vehicle configuration
+      file, this Load() method is called. All external forces will be parsed, and 
+      a FGExternalForce object will be instantiated for each force definition.
+      @param el a pointer to the XML element holding the external reactions definition.
+  */
+  bool Load(Element* el);
+
+  /** Retrieves the total forces defined in the external reactions.
+      @return the total force in pounds.
+  */
+  FGColumnVector3 GetForces(void) {return vTotalForces;}
+
+  /** Retrieves the total moment resulting from the forces defined in the external reactions.
+      @return the total moment in foot-pounds.
+  */
+  FGColumnVector3 GetMoments(void) {return vTotalMoments;}
+
+private:
+
+  vector <FGExternalForce*> Forces;
+  unsigned int numForces;
+  FGColumnVector3 vTotalForces;
+  FGColumnVector3 vTotalMoments;
+  vector <double*> interface_properties;
+
+  bool NoneDefined;
+
+  void Debug(int from);
+};
+}
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+#endif
+
index cf41c57555baf6a7ed3365ece6449323cf530df4..8dd5fc8f818ba5e9f176576be660fa1b3c3ff43f 100644 (file)
@@ -1,6 +1,6 @@
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
- Module:       FGFCS.cpp
+ Module:       FGFCS.cpp 
  Author:       Jon Berndt
  Date started: 12/12/98
  Purpose:      Model the flight controls
@@ -90,11 +90,6 @@ FGFCS::FGFCS(FGFDMExec* fdmex) : FGModel(fdmex)
 
 FGFCS::~FGFCS()
 {
-  if (PropertyManager->HasNode("fcs")) unbind( PropertyManager->GetNode("fcs") );
-  if (PropertyManager->HasNode("ap")) unbind( PropertyManager->GetNode("ap") );
-  PropertyManager->Untie( "gear/gear-cmd-norm" );
-  PropertyManager->Untie( "gear/gear-pos-norm" );
-
   ThrottleCmd.clear();
   ThrottlePos.clear();
   MixtureCmd.clear();
@@ -107,18 +102,47 @@ FGFCS::~FGFCS()
 
   unsigned int i;
 
-  for (i=0;i<APComponents.size();i++) delete APComponents[i];
-  for (i=0;i<FCSComponents.size();i++) delete FCSComponents[i];
   for (i=0;i<sensors.size();i++) delete sensors[i];
-
+  sensors.clear();
+  for (i=0;i<APComponents.size();i++) delete APComponents[i];
   APComponents.clear();
+  for (i=0;i<FCSComponents.size();i++) delete FCSComponents[i];
   FCSComponents.clear();
-  sensors.clear();
+  for (i=0;i<Systems.size();i++) delete Systems[i];
+  Systems.clear();
+
+  for (unsigned int i=0; i<interface_properties.size(); i++) delete interface_properties[i];
   interface_properties.clear();
 
   Debug(1);
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGFCS::InitModel(void)
+{
+  unsigned int i;
+
+  if (!FGModel::InitModel()) return false;
+
+  for (i=0; i<ThrottlePos.size(); i++) ThrottlePos[i] = 0.0;
+  for (i=0; i<MixturePos.size(); i++) MixturePos[i] = 0.0;
+  for (i=0; i<ThrottleCmd.size(); i++) ThrottleCmd[i] = 0.0;
+  for (i=0; i<MixtureCmd.size(); i++) MixtureCmd[i] = 0.0;
+  for (i=0; i<PropAdvance.size(); i++) PropAdvance[i] = 0.0;
+  for (i=0; i<PropFeather.size(); i++) PropFeather[i] = 0.0;
+
+  DaCmd = DeCmd = DrCmd = DsCmd = DfCmd = DsbCmd = DspCmd = 0;
+  PTrimCmd = YTrimCmd = RTrimCmd = 0.0;
+
+  for (i=0;i<NForms;i++) {
+    DePos[i] = DaLPos[i] = DaRPos[i] = DrPos[i] = 0.0;
+    DfPos[i] = DsbPos[i] = DspPos[i] = 0.0;
+  }
+
+  return true;
+}
+  
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 // Notes: In this logic the default engine commands are set. This is simply a
 // sort of safe-mode method in case the user has not defined control laws for
@@ -139,18 +163,23 @@ bool FGFCS::Run(void)
   for (i=0; i<PropAdvance.size(); i++) PropAdvance[i] = PropAdvanceCmd[i];
   for (i=0; i<PropFeather.size(); i++) PropFeather[i] = PropFeatherCmd[i];
 
-
   // Set the default steering angle
   for (i=0; i<SteerPosDeg.size(); i++) {
     FGLGear* gear = GroundReactions->GetGearUnit(i);
     SteerPosDeg[i] = gear->GetDefaultSteerAngle( GetDsCmd() );
   }
 
-  // Cycle through the sensor, autopilot, and flight control components
+  // Cycle through the sensor, systems, autopilot, and flight control components
+  // Execute Sensors
   for (i=0; i<sensors.size(); i++) sensors[i]->Run();
-  for (i=0; i<APComponents.size(); i++) {
-    APComponents[i]->Run();
-  }
+
+  // Execute Systems in order
+  for (i=0; i<Systems.size(); i++) Systems[i]->Run();
+
+  // Execute Autopilot
+  for (i=0; i<APComponents.size(); i++) APComponents[i]->Run();
+
+  // Execute Flight Control System
   for (i=0; i<FCSComponents.size(); i++) FCSComponents[i]->Run();
 
   return false;
@@ -455,32 +484,38 @@ void FGFCS::SetPropFeather(int engineNum, bool setting)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-bool FGFCS::Load(Element* el)
+bool FGFCS::Load(Element* el, SystemType systype)
 {
-  string name, file, fname, interface_property_string;
+  string name, file, fname, interface_property_string, parent_name;
   vector <FGFCSComponent*> *Components;
   Element *component_element, *property_element, *sensor_element;
   Element *channel_element;
 
   Components=0;
-  // Determine if the FCS/Autopilot is defined inline in the aircraft configuration
-  // file or in a separate file. Set up the Element pointer as appropriate.
 
   string separator = "/";
 #ifdef macintosh
   separator = ";";
 #endif
 
+// ToDo: The handling of name and file attributes could be improved, here,
+//       considering that a name can be in the external file, as well.
+
   name = el->GetAttributeValue("name");
 
   if (name.empty()) {
     fname = el->GetAttributeValue("file");
+    if (systype == stSystem) {
+      file = FindSystemFullPathname(fname);
+    } else { 
     file = FDMExec->GetFullAircraftPath() + separator + fname + ".xml";
+    }
     if (fname.empty()) {
-      cerr << "FCS/Autopilot does not appear to be defined inline nor in a file" << endl;
+      cerr << "FCS, Autopilot, or system does not appear to be defined inline nor in a file" << endl;
       return false;
     } else {
       document = LoadXMLDocument(file);
+      name = document->GetAttributeValue("name");
     }
   } else {
     document = el;
@@ -492,8 +527,10 @@ bool FGFCS::Load(Element* el)
   } else if (document->GetName() == "flight_control") {
     Components = &FCSComponents;
     Name = "FCS: " + document->GetAttributeValue("name");
+  } else if (document->GetName() == "system") {
+    Components = &Systems;
+    Name = "System: " + document->GetAttributeValue("name");
   }
-
   Debug(2);
 
   // ToDo: How do these get untied?
@@ -504,14 +541,25 @@ bool FGFCS::Load(Element* el)
 
   if (document->GetName() == "flight_control") bindModel();
 
+  // Interface properties from any autopilot, flight control, or other system are
+  // all stored in the interface properties array.
+
   property_element = document->FindElement("property");
   while (property_element) {
-    interface_properties.push_back(new double(0));
+    double value=0.0;
+    if ( ! property_element->GetAttributeValue("value").empty())
+      value = property_element->GetAttributeValueAsNumber("value");
+    interface_properties.push_back(new double(value));
     interface_property_string = property_element->GetDataLine();
     PropertyManager->Tie(interface_property_string, interface_properties.back());
     property_element = document->FindNextElement("property");
   }
 
+  // Any sensor elements that are outside of a channel (in either the autopilot
+  // or the flight_control, or even any possible "system") are placed into the global
+  // "sensors" array, and are executed prior to any autopilot, flight control, or
+  // system.
+
   sensor_element = document->FindElement("sensor");
   while (sensor_element) {
     try {
@@ -554,6 +602,8 @@ bool FGFCS::Load(Element* el)
           Components->push_back(new FGPID(this, component_element));
         } else if (component_element->GetName() == string("actuator")) {
           Components->push_back(new FGActuator(this, component_element));
+        } else if (component_element->GetName() == string("sensor")) {
+          Components->push_back(new FGSensor(this, component_element));
         } else {
           cerr << "Unknown FCS component: " << component_element->GetName() << endl;
         }
@@ -567,6 +617,8 @@ bool FGFCS::Load(Element* el)
     channel_element = document->FindNextElement("channel");
   }
 
+  ResetParser();
+
   return true;
 }
 
@@ -589,17 +641,78 @@ double FGFCS::GetBrake(FGLGear::BrakeGroup bg)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+string FGFCS::FindSystemFullPathname(string system_filename)
+{
+  string fullpath, localpath;
+  string systemPath = FDMExec->GetSystemsPath();
+  string aircraftPath = FDMExec->GetFullAircraftPath();
+  ifstream system_file;
+
+  string separator = "/";
+# ifdef macintosh
+  separator = ";";
+# endif
+
+  fullpath = systemPath + separator;
+  localpath = aircraftPath + separator + "Systems" + separator;
+
+  system_file.open(string(fullpath + system_filename + ".xml").c_str());
+  if ( !system_file.is_open()) {
+    system_file.open(string(localpath + system_filename + ".xml").c_str());
+      if ( !system_file.is_open()) {
+        cerr << " Could not open system file: " << system_filename << " in path "
+             << fullpath << " or " << localpath << endl;
+        return string("");
+      } else {
+        return string(localpath + system_filename + ".xml");
+      }
+  }
+  return string(fullpath + system_filename + ".xml");
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ifstream* FGFCS::FindSystemFile(string system_filename)
+{
+  string fullpath, localpath;
+  string systemPath = FDMExec->GetSystemsPath();
+  string aircraftPath = FDMExec->GetFullAircraftPath();
+  ifstream* system_file = new ifstream();
+
+  string separator = "/";
+# ifdef macintosh
+  separator = ";";
+# endif
+
+  fullpath = systemPath + separator;
+  localpath = aircraftPath + separator + "Systems" + separator;
+
+  system_file->open(string(fullpath + system_filename + ".xml").c_str());
+  if ( !system_file->is_open()) {
+    system_file->open(string(localpath + system_filename + ".xml").c_str());
+      if ( !system_file->is_open()) {
+        cerr << " Could not open system file: " << system_filename << " in path "
+             << fullpath << " or " << localpath << endl;
+      }
+  }
+  return system_file;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 string FGFCS::GetComponentStrings(string delimeter)
 {
   unsigned int comp;
   string CompStrings = "";
   bool firstime = true;
+  int total_count=0;
 
-  for (comp = 0; comp < FCSComponents.size(); comp++) {
+  for (unsigned int i=0; i<Systems.size(); i++) {
     if (firstime) firstime = false;
     else          CompStrings += delimeter;
 
-    CompStrings += FCSComponents[comp]->GetName();
+    CompStrings += Systems[i]->GetName();
+    total_count++;
   }
 
   for (comp = 0; comp < APComponents.size(); comp++)
@@ -608,6 +721,15 @@ string FGFCS::GetComponentStrings(string delimeter)
     else          CompStrings += delimeter;
 
     CompStrings += APComponents[comp]->GetName();
+    total_count++;
+  }
+
+  for (comp = 0; comp < FCSComponents.size(); comp++) {
+    if (firstime) firstime = false;
+    else          CompStrings += delimeter;
+
+    CompStrings += FCSComponents[comp]->GetName();
+    total_count++;
   }
 
   return CompStrings;
@@ -619,15 +741,17 @@ string FGFCS::GetComponentValues(string delimeter)
 {
   unsigned int comp;
   string CompValues = "";
-  char buffer[17];
+  char buffer[20];
   bool firstime = true;
+  int total_count=0;
 
-  for (comp = 0; comp < FCSComponents.size(); comp++) {
+  for (unsigned int i=0; i<Systems.size(); i++) {
     if (firstime) firstime = false;
     else          CompValues += delimeter;
 
-    sprintf(buffer, "%9.6f", FCSComponents[comp]->GetOutput());
+    sprintf(buffer, "%9.6f", Systems[i]->GetOutput());
     CompValues += string(buffer);
+    total_count++;
   }
 
   for (comp = 0; comp < APComponents.size(); comp++) {
@@ -636,6 +760,16 @@ string FGFCS::GetComponentValues(string delimeter)
 
     sprintf(buffer, "%9.6f", APComponents[comp]->GetOutput());
     CompValues += string(buffer);
+    total_count++;
+  }
+
+  for (comp = 0; comp < FCSComponents.size(); comp++) {
+    if (firstime) firstime = false;
+    else          CompValues += delimeter;
+
+    sprintf(buffer, "%9.6f", FCSComponents[comp]->GetOutput());
+    CompValues += string(buffer);
+    total_count++;
   }
 
   CompValues += "\0";
@@ -779,20 +913,6 @@ void FGFCS::bindModel(void)
   }
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGFCS::unbind(FGPropertyManager *node)
-{
-  int N = node->nChildren();
-  for (int i=0; i<N; i++) {
-    if (node->getChild(i)->nChildren() ) {
-      unbind( (FGPropertyManager*)node->getChild(i) );
-    } else if ( node->getChild(i)->isTied() ) {
-      node->getChild(i)->untie();
-    }
-  }
-}
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index b07800fb71345ead5b440dbaa7464c02544343d4..3868118ca6280fe9521f33b741dd1b57a5f1ffcb 100644 (file)
@@ -74,12 +74,13 @@ CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 /** Encapsulates the Flight Control System (FCS) functionality.
-    This class owns and contains the list of FGFCSComponents
-    that define the control system for this aircraft. The config file for the
-    aircraft contains a description of the control path that starts at an input
-    or command and ends at an effector, e.g. an aerosurface. The FCS components
-    which comprise the control laws for an axis are defined sequentially in
-    the configuration file. For instance, for the X-15:
+    This class also encapsulates the identical "system" and "autopilot" capability.
+    FGFCS owns and contains the list of FGFCSComponents
+    that define a system or systems for the modeled aircraft. The config file
+    for the aircraft contains a description of the control path that starts at
+    an input or command and ends at an effector, e.g. an aerosurface. The FCS
+    components which comprise the control laws for an axis are defined
+    sequentially in the configuration file. For instance, for the X-15:
 
     @code
     <flight_control name="X-15 SAS">
@@ -119,14 +120,14 @@ CLASS DOCUMENTATION
     addition to using the "NAME" attribute in,
 
     @code
-    \<flight_control name="X-15 SAS">
+    <flight_control name="X-15 SAS">
     @endcode
 
     one can also supply a filename:
 
     @code
-    \<flight_control name="X-15 SAS" file="X15.xml">
-    \</flight_control>
+    <flight_control name="X-15 SAS" file="X15.xml">
+    </flight_control>
     @endcode
 
     In this case, the FCS would be read in from another file.
@@ -174,17 +175,18 @@ CLASS DOCUMENTATION
 
     @author Jon S. Berndt
     @version $Revision$
-    @see FGFCSComponent
-    @see FGXMLElement
-    @see FGGain
-    @see FGSummer
-    @see FGSwitch
+    @see FGActuator
+    @see FGDeadBand
     @see FGFCSFunction
-    @see FGCondition
-    @see FGGradient
     @see FGFilter
-    @see FGDeadBand
+    @see FGGain
     @see FGKinemat
+    @see FGPID
+    @see FGSensor
+    @see FGSummer
+    @see FGSwitch
+    @see FGFCSComponent
+    @see Element
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -201,6 +203,8 @@ public:
   /// Destructor
   ~FGFCS();
 
+  bool InitModel(void);
+
   /** Runs the Flight Controls model; called by the Executive
       @return false if no error */
   bool Run(void);
@@ -516,11 +520,17 @@ public:
   double GetCBrake(void) const {return CenterBrake;}
   //@}
 
+  enum SystemType { stFCS, stSystem, stAutoPilot }; 
+
   /** Loads the Flight Control System.
       Load() is called from FGFDMExec.
       @param el pointer to the Element instance
+      @param systype type of system (FCS, Autopilot, System) 
       @return true if succesful */
-  bool Load(Element* el);
+  bool Load(Element* el, SystemType systype);
+
+  ifstream* FindSystemFile(string system_filename);
+  string FindSystemFullPathname(string system_filename);
 
   void AddThrottle(void);
   void AddGear(void);
@@ -545,14 +555,15 @@ private:
   double LeftBrake, RightBrake, CenterBrake; // Brake settings
   double GearCmd,GearPos;
 
-  vector <FGFCSComponent*> FCSComponents;
-  vector <FGFCSComponent*> APComponents;
+  typedef vector <FGFCSComponent*> FCSCompVec;
+  FCSCompVec Systems;
+  FCSCompVec FCSComponents;
+  FCSCompVec APComponents;
+  FCSCompVec sensors;
   vector <double*> interface_properties;
-  vector <FGFCSComponent*> sensors;
   void bind(void);
   void bindModel(void);
   void bindThrottle(unsigned int);
-  void unbind(FGPropertyManager *node);
   void Debug(int from);
 };
 }
diff --git a/src/FDM/JSBSim/models/FGGasCell.cpp b/src/FDM/JSBSim/models/FGGasCell.cpp
new file mode 100644 (file)
index 0000000..255b7ab
--- /dev/null
@@ -0,0 +1,874 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Header:       FGGasCell.h
+ Author:       Anders Gidenstam
+ Date started: 01/21/2006
+
+ ----- Copyright (C) 2006 - 2008  Anders Gidenstam (anders(at)gidenstam.org) --
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+FUNCTIONAL DESCRIPTION
+--------------------------------------------------------------------------------
+See header file.
+
+HISTORY
+--------------------------------------------------------------------------------
+01/21/2006  AG   Created
+
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#include <FGFDMExec.h>
+#include <models/FGAuxiliary.h>
+#include <models/FGAtmosphere.h>
+#include <models/FGInertial.h>
+#include <models/FGMassBalance.h>
+#include "FGGasCell.h"
+
+#if !defined ( sgi ) || defined( __GNUC__ ) && (_COMPILER_VERSION < 740)
+using std::cerr;
+using std::endl;
+using std::cout;
+#endif
+
+namespace JSBSim {
+
+static const char *IdSrc = "$Id$";
+static const char *IdHdr = ID_GASCELL;
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS IMPLEMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+/* Constants. */
+const double FGGasCell::R = 3.4071;              // [lbs ft/(mol Rankine)]
+const double FGGasCell::M_air = 0.0019186;       // [slug/mol]
+const double FGGasCell::M_hydrogen = 0.00013841; // [slug/mol]
+const double FGGasCell::M_helium = 0.00027409;   // [slug/mol]
+
+FGGasCell::FGGasCell(FGFDMExec* exec, Element* el, int num) : FGForce(exec)
+{
+  string token;
+  Element* element;
+
+  Auxiliary = exec->GetAuxiliary();
+  Atmosphere = exec->GetAtmosphere();
+  PropertyManager = exec->GetPropertyManager();
+  Inertial = exec->GetInertial();
+  MassBalance = exec->GetMassBalance();
+
+  gasCellJ = FGMatrix33();
+  gasCellM = FGColumnVector3();
+
+  Buoyancy = MaxVolume = MaxOverpressure = Temperature = Pressure =
+    Contents = Volume = dVolumeIdeal = 0.0;
+  Xradius = Yradius = Zradius = Xwidth = Ywidth = Zwidth = 0.0;
+  ValveCoefficient = ValveOpen = 0.0;
+  CellNum = num;
+
+  // NOTE: In the local system X points north, Y points east and Z points down.
+  SetTransformType(FGForce::tLocalBody);
+
+  type = el->GetAttributeValue("type");
+  if      (type == "HYDROGEN") Type = ttHYDROGEN;
+  else if (type == "HELIUM")   Type = ttHELIUM;
+  else if (type == "AIR")      Type = ttAIR;
+  else                         Type = ttUNKNOWN;
+
+  element = el->FindElement("location");
+  if (element) {
+    vXYZ = element->FindElementTripletConvertTo("IN");
+  } else {
+    cerr << "Fatal Error: No location found for this gas cell." << endl;
+    exit(-1);
+  }
+  if ((el->FindElement("x_radius") || el->FindElement("x_width")) &&
+      (el->FindElement("y_radius") || el->FindElement("y_width")) &&
+      (el->FindElement("z_radius") || el->FindElement("z_width"))) {
+
+    if (el->FindElement("x_radius")) {
+      Xradius = el->FindElementValueAsNumberConvertTo("x_radius", "FT");
+    }
+    if (el->FindElement("y_radius")) {
+      Yradius = el->FindElementValueAsNumberConvertTo("y_radius", "FT");
+    }
+    if (el->FindElement("z_radius")) {
+      Zradius = el->FindElementValueAsNumberConvertTo("z_radius", "FT");
+    }
+
+    if (el->FindElement("x_width")) {
+      Xwidth = el->FindElementValueAsNumberConvertTo("x_width", "FT");
+    }
+    if (el->FindElement("y_width")) {
+      Ywidth = el->FindElementValueAsNumberConvertTo("y_width", "FT");
+    }
+    if (el->FindElement("z_width")) {
+      Zwidth = el->FindElementValueAsNumberConvertTo("z_width", "FT");
+    }
+
+    // The volume is a (potentially) extruded ellipsoid.
+    // However, currently only a few combinations of radius and width are
+    // fully supported.
+    if ((Xradius != 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+        (Xwidth  == 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+      // Ellipsoid volume.
+      MaxVolume = 4.0  * M_PI * Xradius * Yradius * Zradius / 3.0;
+    } else if  ((Xradius == 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+                (Xwidth  != 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+      // Cylindrical volume.
+      MaxVolume = M_PI * Yradius * Zradius * Xwidth;
+    } else {
+      cerr << "Warning: Unsupported gas cell shape." << endl;
+      MaxVolume = 
+        (4.0  * M_PI * Xradius * Yradius * Zradius / 3.0 +
+         M_PI * Yradius * Zradius * Xwidth +
+         M_PI * Xradius * Zradius * Ywidth +
+         M_PI * Xradius * Yradius * Zwidth +
+         2.0  * Xradius * Ywidth * Zwidth +
+         2.0  * Yradius * Xwidth * Zwidth +
+         2.0  * Zradius * Xwidth * Ywidth +
+         Xwidth * Ywidth * Zwidth);
+    }
+  } else {
+    cerr << "Fatal Error: Gas cell shape must be given." << endl;
+    exit(-1);
+  }
+  if (el->FindElement("max_overpressure")) {
+    MaxOverpressure = el->FindElementValueAsNumberConvertTo("max_overpressure",
+                                                            "LBS/FT2");
+  }
+  if (el->FindElement("fullness")) {
+    const double Fullness = el->FindElementValueAsNumber("fullness");
+    if (0 <= Fullness) { 
+      Volume = Fullness * MaxVolume; 
+    } else {
+      cerr << "Warning: Invalid initial gas cell fullness value." << endl;
+    }
+  }  
+  if (el->FindElement("valve_coefficient")) {
+    ValveCoefficient =
+      el->FindElementValueAsNumberConvertTo("valve_coefficient",
+                                            "FT4*SEC/SLUG");
+    ValveCoefficient = max(ValveCoefficient, 0.0);
+  }
+
+  // Initialize state
+  SetLocation(vXYZ);
+
+  if (Temperature == 0.0) {
+    Temperature = Atmosphere->GetTemperature();
+  }
+  if (Pressure == 0.0) {
+    Pressure = Atmosphere->GetPressure();
+  }
+  if (Volume != 0.0) {
+    // Calculate initial gas content.
+    Contents = Pressure * Volume / (R * Temperature);
+    
+    // Clip to max allowed value.
+    const double IdealPressure = Contents * R * Temperature / MaxVolume;
+    if (IdealPressure > Pressure + MaxOverpressure) {
+      Contents = (Pressure + MaxOverpressure) * MaxVolume / (R * Temperature);
+      Pressure = Pressure + MaxOverpressure;
+    } else {
+      Pressure = max(IdealPressure, Pressure);
+    }
+  } else {
+    // Calculate initial gas content.
+    Contents = Pressure * MaxVolume / (R * Temperature);
+  }
+
+  Volume = Contents * R * Temperature / Pressure;
+  Mass = Contents * M_gas();
+
+  // Bind relevant properties
+  char property_name[80];
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/max_volume-ft3",
+           CellNum);
+  PropertyManager->Tie( property_name, &MaxVolume );
+  PropertyManager->SetWritable( property_name, false );
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/temp-R",
+           CellNum);
+  PropertyManager->Tie( property_name, &Temperature );
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/pressure-psf",
+           CellNum);
+  PropertyManager->Tie( property_name, &Pressure );
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/volume-ft3",
+           CellNum);
+  PropertyManager->Tie( property_name, &Volume );
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/buoyancy-lbs",
+           CellNum);
+  PropertyManager->Tie( property_name, &Buoyancy );
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/contents-mol",
+           CellNum);
+  PropertyManager->Tie( property_name, &Contents );
+  snprintf(property_name, 80, "buoyant_forces/gas-cell[%d]/valve_open",
+           CellNum);
+  PropertyManager->Tie( property_name, &ValveOpen );
+
+  Debug(0);
+
+  // Read heat transfer coefficients
+  if (Element* heat = el->FindElement("heat")) {
+    Element* function_element = heat->FindElement("function");
+    while (function_element) {
+      HeatTransferCoeff.push_back(new FGFunction(PropertyManager,
+                                                 function_element));
+      function_element = heat->FindNextElement("function");
+    }
+  }
+
+  // Load ballonets if there are any
+  if (Element* ballonet_element = el->FindElement("ballonet")) {
+    while (ballonet_element) {
+      Ballonet.push_back(new FGBallonet(exec,
+                                        ballonet_element,
+                                        Ballonet.size(),
+                                        this));
+      ballonet_element = el->FindNextElement("ballonet");
+    }
+  }
+
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGGasCell::~FGGasCell()
+{
+  unsigned int i;
+
+  for (i = 0; i < HeatTransferCoeff.size(); i++) delete HeatTransferCoeff[i];
+  HeatTransferCoeff.clear();
+
+  for (i = 0; i < Ballonet.size(); i++) delete Ballonet[i];
+  Ballonet.clear();
+
+  Debug(1);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGGasCell::Calculate(double dt)
+{
+  const double AirTemperature = Atmosphere->GetTemperature();  // [Rankine]
+  const double AirPressure    = Atmosphere->GetPressure();     // [lbs/ft²]
+  const double AirDensity     = Atmosphere->GetDensity();      // [slug/ft³]
+  const double g = Inertial->gravity();                        // [lbs/slug]
+
+  const double OldTemperature = Temperature;
+  const double OldPressure    = Pressure;
+  unsigned int i;
+  const unsigned int no_ballonets = Ballonet.size();
+
+  //-- Read ballonet state --
+  // NOTE: This model might need a more proper integration technique. 
+  double BallonetsVolume = 0.0;
+  double BallonetsHeatFlow = 0.0;
+  for (i = 0; i < no_ballonets; i++) {
+    BallonetsVolume   += Ballonet[i]->GetVolume();
+    BallonetsHeatFlow += Ballonet[i]->GetHeatFlow();
+  }
+
+  //-- Gas temperature --
+
+  if (HeatTransferCoeff.size() > 0) {
+    // The model is based on the ideal gas law.
+    // However, it does look a bit fishy. Please verify.
+    //   dT/dt = dU / (Cv n R)
+    double dU = 0.0;
+    for (i = 0; i < HeatTransferCoeff.size(); i++) {
+      dU += HeatTransferCoeff[i]->GetValue();
+    }
+    // Don't include dt when accounting for adiabatic expansion/contraction.
+    // The rate of adiabatic cooling looks about right: ~5.4 Rankine/1000ft. 
+    if (Contents > 0) {
+      Temperature +=
+        (dU * dt - Pressure * dVolumeIdeal - BallonetsHeatFlow) /
+        (Cv_gas() * Contents * R);
+    } else {
+      Temperature = AirTemperature;
+    }
+  } else {
+    // No simulation of complex temperature changes.
+    // Note: Making the gas cell behave adiabatically might be a better
+    // option.
+    Temperature = AirTemperature;
+  }
+
+  //-- Pressure --
+  const double IdealPressure =
+    Contents * R * Temperature / (MaxVolume - BallonetsVolume);
+  if (IdealPressure > AirPressure + MaxOverpressure) {
+    Pressure = AirPressure + MaxOverpressure;
+  } else {
+    Pressure = max(IdealPressure, AirPressure);
+  }
+
+  //-- Manual valving --
+
+  // FIXME: Presently the effect of manual valving is computed using
+  //        an ad hoc formula which might not be a good representation
+  //        of reality.
+  if ((ValveCoefficient > 0.0) && (ValveOpen > 0.0)) {
+    // First compute the difference in pressure between the gas in the
+    // cell and the air above it.
+    // FixMe: CellHeight should depend on current volume.
+    const double CellHeight = 2 * Zradius + Zwidth;                   // [ft]
+    const double GasMass    = Contents * M_gas();                     // [slug]
+    const double GasVolume  = Contents * R * Temperature / Pressure;  // [ft³]
+    const double GasDensity = GasMass / GasVolume;
+    const double DeltaPressure =
+      Pressure + CellHeight * g * (AirDensity - GasDensity) - AirPressure;
+    const double VolumeValved =
+      ValveOpen * ValveCoefficient * DeltaPressure * dt;
+    Contents =
+      max(0.0, Contents - Pressure * VolumeValved / (R * Temperature));
+  }
+
+  //-- Update ballonets. --
+  // Doing that here should give them the opportunity to react to the
+  // new pressure.
+  BallonetsVolume = 0.0;
+  for (i = 0; i < no_ballonets; i++) {
+    Ballonet[i]->Calculate(dt);
+    BallonetsVolume += Ballonet[i]->GetVolume();
+  }
+
+  //-- Automatic safety valving. --
+  if (Contents * R * Temperature / (MaxVolume - BallonetsVolume) >
+      AirPressure + MaxOverpressure) {
+    // Gas is automatically valved. Valving capacity is assumed to be infinite.
+    // FIXME: This could/should be replaced by damage to the gas cell envelope.
+    Contents =
+      (AirPressure + MaxOverpressure) *
+      (MaxVolume - BallonetsVolume) / (R * Temperature);
+  }
+
+  //-- Volume --
+  Volume = Contents * R * Temperature / Pressure + BallonetsVolume;
+  dVolumeIdeal =
+    Contents * R * (Temperature / Pressure - OldTemperature / OldPressure);
+
+  //-- Current buoyancy --
+  // The buoyancy is computed using the atmospheres local density.
+  Buoyancy = Volume * AirDensity * g;
+  
+  // Note: This is gross buoyancy. The weight of the gas itself and
+  // any ballonets is not deducted here as the effects of the gas mass
+  // is handled by FGMassBalance.
+  vFn.InitMatrix(0.0, 0.0, - Buoyancy);
+
+  // Compute the inertia of the gas cell.
+  // Consider the gas cell as a shape of uniform density.
+  // FIXME: If the cell isn't ellipsoid or cylindrical the inertia will
+  //        be wrong.
+  gasCellJ = FGMatrix33();
+  const double mass = Contents * M_gas();
+  double Ixx, Iyy, Izz;
+  if ((Xradius != 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+      (Xwidth  == 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+    // Ellipsoid volume.
+    Ixx = (1.0 / 5.0) * mass * (Yradius*Yradius + Zradius*Zradius);
+    Iyy = (1.0 / 5.0) * mass * (Xradius*Xradius + Zradius*Zradius);
+    Izz = (1.0 / 5.0) * mass * (Xradius*Xradius + Yradius*Yradius);     
+  } else if  ((Xradius == 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+              (Xwidth  != 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+    // Cylindrical volume (might not be valid with an elliptical cross-section).
+    Ixx = (1.0 / 2.0) * mass * Yradius * Zradius;
+    Iyy =
+      (1.0 / 4.0) * mass * Yradius * Zradius +
+      (1.0 / 12.0) * mass * Xwidth * Xwidth;
+    Izz =
+      (1.0 / 4.0) * mass * Yradius * Zradius +
+      (1.0 / 12.0) * mass * Xwidth * Xwidth;
+  } else {
+    // Not supported. Revert to pointmass model.
+    Ixx = Iyy = Izz = 0.0;
+  }
+  // The volume is symmetric, so Ixy = Ixz = Iyz = 0.
+  gasCellJ(1,1) = Ixx;
+  gasCellJ(2,2) = Iyy;
+  gasCellJ(3,3) = Izz;
+  Mass = mass;
+  gasCellM.InitMatrix();
+  gasCellM(eX) +=
+    GetXYZ(eX) * Mass*slugtolb;
+  gasCellM(eY) +=
+    GetXYZ(eY) * Mass*slugtolb;
+  gasCellM(eZ) +=
+    GetXYZ(eZ) * Mass*slugtolb;
+
+  if (no_ballonets > 0) {
+    // Add the mass, moment and inertia of any ballonets.
+    const FGColumnVector3 p = MassBalance->StructuralToBody( GetXYZ() );
+
+    for (i = 0; i < no_ballonets; i++) {
+      Mass += Ballonet[i]->GetMass();
+       
+      // Add ballonet moments.
+      gasCellM(eX) +=
+        Ballonet[i]->GetXYZ(eX) * Ballonet[i]->GetMass()*slugtolb;
+      gasCellM(eY) +=
+        Ballonet[i]->GetXYZ(eY) * Ballonet[i]->GetMass()*slugtolb;
+      gasCellM(eZ) +=
+        Ballonet[i]->GetXYZ(eZ) * Ballonet[i]->GetMass()*slugtolb;
+      
+      // Moments of inertia must be converted to the gas cell frame here.
+      FGColumnVector3 v =
+        MassBalance->StructuralToBody( Ballonet[i]->GetXYZ() ) - p;
+      // Body basis is in FT. 
+      const double mass = Ballonet[i]->GetMass();
+      gasCellJ += Ballonet[i]->GetInertia() +
+        FGMatrix33( 0,                - mass*v(1)*v(2), - mass*v(1)*v(3),
+                    - mass*v(2)*v(1), 0,                - mass*v(2)*v(3),
+                    - mass*v(3)*v(1), - mass*v(3)*v(2), 0 );
+    }
+  }
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//    The bitmasked value choices are as follows:
+//    unset: In this case (the default) JSBSim would only print
+//       out the normally expected messages, essentially echoing
+//       the config files as they are read. If the environment
+//       variable is not set, debug_lvl is set to 1 internally
+//    0: This requests JSBSim not to output any messages
+//       whatsoever.
+//    1: This value explicity requests the normal JSBSim
+//       startup messages
+//    2: This value asks for a message to be printed out when
+//       a class is instantiated
+//    4: When this value is set, a message is displayed when a
+//       FGModel object executes its Run() method
+//    8: When this value is set, various runtime state variables
+//       are printed out periodically
+//    16: When set various parameters are sanity checked and
+//       a message is printed out when they go out of bounds
+
+void FGGasCell::Debug(int from)
+{
+  if (debug_lvl <= 0) return;
+
+  if (debug_lvl & 1) { // Standard console startup message output
+    if (from == 0) { // Constructor
+      cout << "    Gas cell holds " << Contents << " mol " <<
+        type << endl;
+      cout << "      Cell location (X, Y, Z) (in.): " << vXYZ(eX) << ", " <<
+        vXYZ(eY) << ", " << vXYZ(eZ) << endl;
+      cout << "      Maximum volume: " << MaxVolume << " ft3" << endl;
+      cout << "      Relief valve release pressure: " << MaxOverpressure << 
+        " lbs/ft2" << endl;
+      cout << "      Manual valve coefficient: " << ValveCoefficient << 
+        " ft4*sec/slug" << endl;
+      cout << "      Initial temperature: " << Temperature << " Rankine" <<
+        endl;
+      cout << "      Initial pressure: " << Pressure << " lbs/ft2" << endl;
+      cout << "      Initial volume: " << Volume << " ft3" << endl;
+      cout << "      Initial mass: " << GetMass() << " slug mass" << endl;
+      cout << "      Initial weight: " << GetMass()*lbtoslug << " lbs force" <<
+        endl;
+      cout << "      Heat transfer: " << endl;
+    }
+  }
+  if (debug_lvl & 2 ) { // Instantiation/Destruction notification
+    if (from == 0) cout << "Instantiated: FGGasCell" << endl;
+    if (from == 1) cout << "Destroyed:    FGGasCell" << endl;
+  }
+  if (debug_lvl & 4 ) { // Run() method entry print for FGModel-derived objects
+  }
+  if (debug_lvl & 8 ) { // Runtime state variables    
+      cout << "      " << type << " cell holds " << Contents << " mol " << endl;
+      cout << "      Temperature: " << Temperature << " Rankine" << endl;
+      cout << "      Pressure: " << Pressure << " lbs/ft2" << endl;
+      cout << "      Volume: " << Volume << " ft3" << endl;
+      cout << "      Mass: " << GetMass() << " slug mass" << endl;
+      cout << "      Weight: " << GetMass()*lbtoslug << " lbs force" << endl;
+  }
+  if (debug_lvl & 16) { // Sanity checking
+  }
+  if (debug_lvl & 64) {
+    if (from == 0) { // Constructor
+      cout << IdSrc << endl;
+      cout << IdHdr << endl;
+    }
+  }
+}
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS IMPLEMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+const double FGBallonet::R = 3.4071;              // [lbs ft/(mol Rankine)]
+const double FGBallonet::M_air = 0.0019186;       // [slug/mol]
+const double FGBallonet::Cv_air = 5.0/2.0;        // [??]
+
+FGBallonet::FGBallonet(FGFDMExec* exec, Element* el, int num, FGGasCell* parent)
+{
+  string token;
+  Element* element;
+
+  Auxiliary = exec->GetAuxiliary();
+  Atmosphere = exec->GetAtmosphere();
+  PropertyManager = exec->GetPropertyManager();
+  Inertial = exec->GetInertial();
+
+  ballonetJ = FGMatrix33();
+
+  MaxVolume = MaxOverpressure = Temperature = Pressure =
+    Contents = Volume = dVolumeIdeal = dU = 0.0;
+  Xradius = Yradius = Zradius = Xwidth = Ywidth = Zwidth = 0.0;
+  ValveCoefficient = ValveOpen = 0.0;
+  BlowerInput = NULL;
+  CellNum = num;
+  Parent = parent;
+
+  // NOTE: In the local system X points north, Y points east and Z points down.
+  element = el->FindElement("location");
+  if (element) {
+    vXYZ = element->FindElementTripletConvertTo("IN");
+  } else {
+    cerr << "Fatal Error: No location found for this ballonet." << endl;
+    exit(-1);
+  }
+  if ((el->FindElement("x_radius") || el->FindElement("x_width")) &&
+      (el->FindElement("y_radius") || el->FindElement("y_width")) &&
+      (el->FindElement("z_radius") || el->FindElement("z_width"))) {
+
+    if (el->FindElement("x_radius")) {
+      Xradius = el->FindElementValueAsNumberConvertTo("x_radius", "FT");
+    }
+    if (el->FindElement("y_radius")) {
+      Yradius = el->FindElementValueAsNumberConvertTo("y_radius", "FT");
+    }
+    if (el->FindElement("z_radius")) {
+      Zradius = el->FindElementValueAsNumberConvertTo("z_radius", "FT");
+    }
+
+    if (el->FindElement("x_width")) {
+      Xwidth = el->FindElementValueAsNumberConvertTo("x_width", "FT");
+    }
+    if (el->FindElement("y_width")) {
+      Ywidth = el->FindElementValueAsNumberConvertTo("y_width", "FT");
+    }
+    if (el->FindElement("z_width")) {
+      Zwidth = el->FindElementValueAsNumberConvertTo("z_width", "FT");
+    }
+
+    // The volume is a (potentially) extruded ellipsoid.
+    // FIXME: However, currently only a few combinations of radius and
+    //        width are fully supported.
+    if ((Xradius != 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+        (Xwidth  == 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+      // Ellipsoid volume.
+      MaxVolume = 4.0  * M_PI * Xradius * Yradius * Zradius / 3.0;
+    } else if  ((Xradius == 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+                (Xwidth  != 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+      // Cylindrical volume.
+      MaxVolume = M_PI * Yradius * Zradius * Xwidth;
+    } else {
+      cerr << "Warning: Unsupported ballonet shape." << endl;
+      MaxVolume = 
+        (4.0  * M_PI * Xradius * Yradius * Zradius / 3.0 +
+         M_PI * Yradius * Zradius * Xwidth +
+         M_PI * Xradius * Zradius * Ywidth +
+         M_PI * Xradius * Yradius * Zwidth +
+         2.0  * Xradius * Ywidth * Zwidth +
+         2.0  * Yradius * Xwidth * Zwidth +
+         2.0  * Zradius * Xwidth * Ywidth +
+         Xwidth * Ywidth * Zwidth);
+    }
+  } else {
+    cerr << "Fatal Error: Ballonet shape must be given." << endl;
+    exit(-1);
+  }
+  if (el->FindElement("max_overpressure")) {
+    MaxOverpressure = el->FindElementValueAsNumberConvertTo("max_overpressure",
+                                                            "LBS/FT2");
+  }
+  if (el->FindElement("fullness")) {
+    const double Fullness = el->FindElementValueAsNumber("fullness");
+    if (0 <= Fullness) { 
+      Volume = Fullness * MaxVolume; 
+    } else {
+      cerr << "Warning: Invalid initial ballonet fullness value." << endl;
+    }
+  }  
+  if (el->FindElement("valve_coefficient")) {
+    ValveCoefficient =
+      el->FindElementValueAsNumberConvertTo("valve_coefficient",
+                                            "FT4*SEC/SLUG");
+    ValveCoefficient = max(ValveCoefficient, 0.0);
+  }
+
+  // Initialize state
+  if (Temperature == 0.0) {
+    Temperature = Parent->GetTemperature();
+  }
+  if (Pressure == 0.0) {
+    Pressure = Parent->GetPressure();
+  }
+  if (Volume != 0.0) {
+    // Calculate initial air content.
+    Contents = Pressure * Volume / (R * Temperature);
+    
+    // Clip to max allowed value.
+    const double IdealPressure = Contents * R * Temperature / MaxVolume;
+    if (IdealPressure > Pressure + MaxOverpressure) {
+      Contents = (Pressure + MaxOverpressure) * MaxVolume / (R * Temperature);
+      Pressure = Pressure + MaxOverpressure;
+    } else {
+      Pressure = max(IdealPressure, Pressure);
+    }
+  } else {
+    // Calculate initial air content.
+    Contents = Pressure * MaxVolume / (R * Temperature);
+  }
+
+  Volume = Contents * R * Temperature / Pressure;
+
+  // Bind relevant properties
+  char property_name[80];
+  snprintf(property_name, 80,
+           "buoyant_forces/gas-cell[%d]/ballonet[%d]/max_volume-ft3",
+           Parent->GetIndex(),
+           CellNum);
+  PropertyManager->Tie( property_name, &MaxVolume );
+  PropertyManager->SetWritable( property_name, false );
+  snprintf(property_name, 80,
+           "buoyant_forces/gas-cell[%d]/ballonet[%d]/temp-R",
+           Parent->GetIndex(),
+           CellNum);
+  PropertyManager->Tie( property_name, &Temperature );
+  snprintf(property_name, 80,
+           "buoyant_forces/gas-cell[%d]/ballonet[%d]/pressure-psf",
+           Parent->GetIndex(),
+           CellNum);
+  PropertyManager->Tie( property_name, &Pressure );
+  snprintf(property_name, 80,
+           "buoyant_forces/gas-cell[%d]/ballonet[%d]/volume-ft3",
+           Parent->GetIndex(),
+           CellNum);
+  PropertyManager->Tie( property_name, &Volume );
+  snprintf(property_name, 80,
+           "buoyant_forces/gas-cell[%d]/ballonet[%d]/contents-mol",
+           Parent->GetIndex(),
+           CellNum);
+  PropertyManager->Tie( property_name, &Contents );
+  snprintf(property_name, 80,
+           "buoyant_forces/gas-cell[%d]/ballonet[%d]/valve_open",
+           Parent->GetIndex(),
+           CellNum);
+  PropertyManager->Tie( property_name, &ValveOpen );
+
+  Debug(0);
+
+  // Read heat transfer coefficients
+  if (Element* heat = el->FindElement("heat")) {
+    Element* function_element = heat->FindElement("function");
+    while (function_element) {
+      HeatTransferCoeff.push_back(new FGFunction(PropertyManager,
+                                                 function_element));
+      function_element = heat->FindNextElement("function");
+    }
+  }
+  // Read blower input function
+  if (Element* blower = el->FindElement("blower_input")) {
+    Element* function_element = blower->FindElement("function");
+    BlowerInput = new FGFunction(PropertyManager,
+                                 function_element);
+  }
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGBallonet::~FGBallonet()
+{
+  unsigned int i;
+
+  for (i = 0; i < HeatTransferCoeff.size(); i++) delete HeatTransferCoeff[i];
+  HeatTransferCoeff.clear();
+
+  delete BlowerInput;
+  BlowerInput = NULL;
+
+  Debug(1);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGBallonet::Calculate(double dt)
+{
+  const double ParentPressure = Parent->GetPressure();         // [lbs/ft²]
+  const double AirPressure    = Atmosphere->GetPressure();     // [lbs/ft²]
+
+  const double OldTemperature = Temperature;
+  const double OldPressure    = Pressure;
+  unsigned int i;
+
+  //-- Gas temperature --
+
+  // The model is based on the ideal gas law.
+  // However, it does look a bit fishy. Please verify.
+  //   dT/dt = dU / (Cv n R)
+  dU = 0.0;
+  for (i = 0; i < HeatTransferCoeff.size(); i++) {
+    dU += HeatTransferCoeff[i]->GetValue();
+  }
+  // dt is already accounted for in dVolumeIdeal.
+  if (Contents > 0) {
+    Temperature +=
+      (dU * dt - Pressure * dVolumeIdeal) / (Cv_air * Contents * R);
+  } else {
+    Temperature = Parent->GetTemperature();
+  }
+
+  //-- Pressure --
+  const double IdealPressure = Contents * R * Temperature / MaxVolume;
+  // The pressure is at least that of the parent gas cell.
+  Pressure = max(IdealPressure, ParentPressure);
+
+  //-- Blower input --
+  if (BlowerInput) {
+    const double AddedVolume = BlowerInput->GetValue() * dt;
+    if (AddedVolume > 0.0) {
+      Contents += Pressure * AddedVolume / (R * Temperature);
+    }
+  }
+
+  //-- Pressure relief and manual valving --
+  // FIXME: Presently the effect of valving is computed using
+  //        an ad hoc formula which might not be a good representation
+  //        of reality.
+  if ((ValveCoefficient > 0.0) &&
+      ((ValveOpen > 0.0) || (Pressure > AirPressure + MaxOverpressure))) {
+    const double DeltaPressure = Pressure - AirPressure;
+    const double VolumeValved =
+      ((Pressure > AirPressure + MaxOverpressure) ? 1.0 : ValveOpen) *
+      ValveCoefficient * DeltaPressure * dt;
+    // FIXME: Too small values of Contents sometimes leads to NaN.
+    //        Currently the minimum is restricted to a safe value.
+    Contents =
+      max(1.0, Contents - Pressure * VolumeValved / (R * Temperature));
+  }
+
+  //-- Volume --
+  Volume = Contents * R * Temperature / Pressure;
+  dVolumeIdeal =
+    Contents * R * (Temperature / Pressure - OldTemperature / OldPressure);
+
+  // Compute the inertia of the ballonet.
+  // Consider the ballonet as a shape of uniform density.
+  // FIXME: If the ballonet isn't ellipsoid or cylindrical the inertia will
+  //        be wrong.
+  ballonetJ = FGMatrix33();
+  const double mass = Contents * M_air;
+  double Ixx, Iyy, Izz;
+  if ((Xradius != 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+      (Xwidth  == 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+    // Ellipsoid volume.
+    Ixx = (1.0 / 5.0) * mass * (Yradius*Yradius + Zradius*Zradius);
+    Iyy = (1.0 / 5.0) * mass * (Xradius*Xradius + Zradius*Zradius);
+    Izz = (1.0 / 5.0) * mass * (Xradius*Xradius + Yradius*Yradius);     
+  } else if  ((Xradius == 0.0) && (Yradius != 0.0) && (Zradius != 0.0) &&
+              (Xwidth  != 0.0) && (Ywidth  == 0.0) && (Zwidth  == 0.0)) {
+    // Cylindrical volume (might not be valid with an elliptical cross-section).
+    Ixx = (1.0 / 2.0) * mass * Yradius * Zradius;
+    Iyy =
+      (1.0 / 4.0) * mass * Yradius * Zradius +
+      (1.0 / 12.0) * mass * Xwidth * Xwidth;
+    Izz =
+      (1.0 / 4.0) * mass * Yradius * Zradius +
+      (1.0 / 12.0) * mass * Xwidth * Xwidth;
+  } else {
+    // Not supported. Revert to pointmass model.
+    Ixx = Iyy = Izz = 0.0;
+  }
+  // The volume is symmetric, so Ixy = Ixz = Iyz = 0.
+  ballonetJ(1,1) = Ixx;
+  ballonetJ(2,2) = Iyy;
+  ballonetJ(3,3) = Izz;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+//    The bitmasked value choices are as follows:
+//    unset: In this case (the default) JSBSim would only print
+//       out the normally expected messages, essentially echoing
+//       the config files as they are read. If the environment
+//       variable is not set, debug_lvl is set to 1 internally
+//    0: This requests JSBSim not to output any messages
+//       whatsoever.
+//    1: This value explicity requests the normal JSBSim
+//       startup messages
+//    2: This value asks for a message to be printed out when
+//       a class is instantiated
+//    4: When this value is set, a message is displayed when a
+//       FGModel object executes its Run() method
+//    8: When this value is set, various runtime state variables
+//       are printed out periodically
+//    16: When set various parameters are sanity checked and
+//       a message is printed out when they go out of bounds
+
+void FGBallonet::Debug(int from)
+{
+  if (debug_lvl <= 0) return;
+
+  if (debug_lvl & 1) { // Standard console startup message output
+    if (from == 0) { // Constructor
+      cout << "      Ballonet holds " << Contents << " mol air" << endl;
+      cout << "        Location (X, Y, Z) (in.): " << vXYZ(eX) << ", " <<
+        vXYZ(eY) << ", " << vXYZ(eZ) << endl;
+      cout << "        Maximum volume: " << MaxVolume << " ft3" << endl;
+      cout << "        Relief valve release pressure: " << MaxOverpressure << 
+        " lbs/ft2" << endl;
+      cout << "        Relief valve coefficient: " << ValveCoefficient << 
+        " ft4*sec/slug" << endl;
+      cout << "        Initial temperature: " << Temperature << " Rankine" <<
+        endl;
+      cout << "        Initial pressure: " << Pressure << " lbs/ft2" << endl;
+      cout << "        Initial volume: " << Volume << " ft3" << endl;
+      cout << "        Initial mass: " << GetMass() << " slug mass" << endl;
+      cout << "        Initial weight: " << GetMass()*lbtoslug <<
+        " lbs force" << endl;
+      cout << "        Heat transfer: " << endl;
+    }
+  }
+  if (debug_lvl & 2 ) { // Instantiation/Destruction notification
+    if (from == 0) cout << "Instantiated: FGBallonet" << endl;
+    if (from == 1) cout << "Destroyed:    FGBallonet" << endl;
+  }
+  if (debug_lvl & 4 ) { // Run() method entry print for FGModel-derived objects
+  }
+  if (debug_lvl & 8 ) { // Runtime state variables    
+      cout << "        Ballonet holds " << Contents <<
+        " mol air" << endl;
+      cout << "        Temperature: " << Temperature << " Rankine" << endl;
+      cout << "        Pressure: " << Pressure << " lbs/ft2" << endl;
+      cout << "        Volume: " << Volume << " ft3" << endl;
+      cout << "        Mass: " << GetMass() << " slug mass" << endl;
+      cout << "        Weight: " << GetMass()*lbtoslug << " lbs force" << endl;
+  }
+  if (debug_lvl & 16) { // Sanity checking
+  }
+  if (debug_lvl & 64) {
+    if (from == 0) { // Constructor
+      cout << IdSrc << endl;
+      cout << IdHdr << endl;
+    }
+  }
+}
+}
diff --git a/src/FDM/JSBSim/models/FGGasCell.h b/src/FDM/JSBSim/models/FGGasCell.h
new file mode 100644 (file)
index 0000000..4c1759a
--- /dev/null
@@ -0,0 +1,386 @@
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+ Header:       FGGasCell.h
+ Author:       Anders Gidenstam
+ Date started: 01/21/2006
+
+ ----- Copyright (C) 2006 - 2008  Anders Gidenstam (anders(at)gidenstam.org) --
+
+ This program is free software; you can redistribute it and/or modify it under
+ the terms of the GNU Lesser General Public License as published by the Free Software
+ Foundation; either version 2 of the License, or (at your option) any later
+ version.
+
+ This program is distributed in the hope that it will be useful, but WITHOUT
+ ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+ FOR A PARTICULAR PURPOSE.  See the GNU Lesser General Public License for more
+ details.
+
+ You should have received a copy of the GNU Lesser General Public License along with
+ this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ Place - Suite 330, Boston, MA  02111-1307, USA.
+
+ Further information about the GNU Lesser General Public License can also be found on
+ the world wide web at http://www.gnu.org.
+
+FUNCTIONAL DESCRIPTION
+--------------------------------------------------------------------------------
+
+This class simulates a generic gas cell for static buoyancy.
+
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+SENTRY
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#ifndef FGGasCell_H
+#define FGGasCell_H
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+INCLUDES
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#include <FGJSBBase.h>
+#include <input_output/FGXMLElement.h>
+#include <math/FGColumnVector3.h>
+#include <models/propulsion/FGForce.h>
+#include <math/FGFunction.h>
+
+#ifdef FGFS
+#  include <simgear/compiler.h>
+#  include STL_STRING
+  SG_USING_STD(string);
+  SG_USING_STD(cerr);
+  SG_USING_STD(endl);
+  SG_USING_STD(cout);
+#else
+# include <string>
+  using std::string;
+# if !defined(sgi) || defined(__GNUC__) || (_COMPILER_VERSION >= 740)
+   using std::cerr;
+   using std::endl;
+   using std::cout;
+# endif
+#endif
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+DEFINITIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+#define ID_GASCELL "$Id$"
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+FORWARD DECLARATIONS
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+namespace JSBSim {
+
+class FGBallonet;
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DOCUMENTATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+
+/** Models a gas cell.
+    @author Anders Gidenstam
+
+<h3>Configuration File Format:</h3>
+@code
+<buoyant_forces>
+  <gas_cell type="{HYDROGEN | HELIUM | AIR}">
+    <location unit="{M | IN}">
+      <x> {number} </x>
+      <y> {number} </y>
+      <z> {number} </z>
+    </location>
+    <x_width unit="{M | IN}"> {number} </x_width>
+    <y_radius unit="{M | IN}"> {number} </y_radius>
+    <z_radius unit="{M | IN}"> {number} </z_radius>
+    <max_overpressure unit="{PA | PSI}"> {number} </max_overpressure>
+    <valve_coefficient unit="{M4*SEC/KG | FT4*SEC/SLUG}"> {number} </valve_coefficient>
+    <fullness> {number} </fullness>  
+    <heat>
+      {heat transfer coefficients} [lbs ft / sec]
+    </heat>
+    <ballonet>
+      <location unit="{M | IN}">
+        <x> {number} </x>
+        <y> {number} </y>
+        <z> {number} </z>
+      </location>
+      <x_width unit="{M | IN}"> {number} </x_width>
+      <y_radius unit="{M | IN}"> {number} </y_radius>
+      <z_radius unit="{M | IN}"> {number} </z_radius>
+      <max_overpressure unit="{PA | PSI}"> {number} </max_overpressure>
+      <valve_coefficient unit="{M4*SEC/KG | FT4*SEC/SLUG}"> {number} </valve_coefficient>
+      <fullness> {number} </fullness>  
+      <heat>
+       {heat transfer coefficients} [lb ft / (sec Rankine)]
+      </heat>
+      <blower_input>
+       {input air flow function} [ft^3 / sec]
+      </blower_input>
+    </ballonet>
+  </gas_cell>
+</buoyant_forces>
+@endcode
+
+Definition of the gas cell configuration file parameters:
+- <b>type</b> -
+    One of HYDROGEN, HELIUM or AIR.
+- <b>location</b> -
+    Location of cell center in the aircraft's structural frame.
+    Currently this is were the forces of the cell is applied.
+- <b>{x|y|z}_radius</b> -
+    Radius along in the respective direction (both ends).
+- <b>{x|y|z}_width</b> -
+    Width in the respective direction.
+    <b>NOTE:</b> A 'x', 'y', 'z'-radius/width combination must be specified.
+- <b>fullness</b> -
+    Initial fullness of the cell, normally [0,1],
+    values >1 initialize the cell at pressure.
+- <b>max_overpressure</b> -
+    Maximum cell overpressure (excess is automatically valved off).
+- <b>valve_coefficient</b> -
+    Capacity of the manual valve. The valve is
+    considered to be located at the top of the cell.
+    The valve coefficient determine the flow out
+    of the cell according to:
+    <i>dVolume/dt = ValveCoefficient * DeltaPressure</i>.
+- <b>heat</b> -
+    Zero or more FGFunction:s describing the heat flow from
+    the atmosphere into the gas cell.
+    Unit: [lb ft / (sec Rankine)].
+    If there are no heat transfer functions at all the gas cell
+    temperature will equal that of the surrounding atmosphere.
+    A constant function returning 0 results in adiabatic behaviour.
+- <b>ballonet</b> -
+    Zero or more ballonets, i.e. air bags inside the gas cell.
+    Ballonets are used to maintain the volume of the gas cell
+    and keep its internal pressure higher than that of the
+    surrounding environment.
+  - <b>location</b> -
+      Location of ballonet center in the aircraft's structural frame.
+  - <b>{x|y|z}_radius</b> -
+      Radius along in the respective direction (both ends).
+  - <b>{x|y|z}_width</b> -
+      Width in the respective direction.
+  - <b>max_overpressure</b> -
+      Maximum ballonet overpressure (excess is automatically valved off).
+  - <b>valve_coefficient</b> -
+      Capacity of the exit valve between the ballonet
+      and the atmosphere. The valve coefficient
+      determine the flow out of the cell according to:
+      <i>dVolume/dt = ValveCoefficient * DeltaPressure</i>.
+  - <b>heat</b> -
+      Zero or more FGFunction:s describing the heat flow from
+      the enclosing gas cell into the ballonet.
+      Unit: [lb ft / (sec Rankine)]
+  - <b>blower_input</b> -
+      One FGFunction describing the air flow into the
+      ballonet. Unit: [ft<sup>3</sup> / sec] (at the temperature and
+      pressure of the ballonet.)
+  */
+
+/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+CLASS DECLARATION
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
+class FGGasCell : public FGForce
+{
+public:
+  /** Constructor
+      @param exec Executive a pointer to the parent executive object
+      @param el   Pointer to configuration file XML node
+      @param num  Gas cell index number. */
+  FGGasCell(FGFDMExec* exec, Element* el, int num);
+  ~FGGasCell();
+
+  /** Runs the gas cell model; called by BuoyantForces
+   */
+  void Calculate(double dt);
+
+  /** Get the index of this gas cell
+      @return gas cell index. */
+  int GetIndex(void) {return CellNum;}
+
+  /** Get the center of gravity location of the gas cell
+      (including any ballonets)
+      @return CoG location in the structural frame. */
+  const FGColumnVector3& GetXYZ(void) {return vXYZ;}
+
+  /** Get the center of gravity location of the gas cell
+      (including any ballonets)
+      @return CoG location in the structural frame. */
+  double GetXYZ(int idx) {return vXYZ(idx);}
+
+  /** Get the current mass of the gas cell (including any ballonets)
+      @return gas mass in slug. */
+  double GetMass(void) {return Mass;}
+
+  /** Get the moments of inertia of the gas cell (including any ballonets)
+      @return moments of inertia matrix in slug ft<sup>2</sup>. */
+  FGMatrix33& GetInertia(void) {return gasCellJ;}
+
+  /** Get the moment due to mass of the gas cell (including any ballonets)
+
+      Note that the buoyancy of the gas cell is handled separately by the
+      FGForce part and not included here.
+      @return moment vector in lbs ft. */
+  FGColumnVector3& GetMassMoment(void) {return gasCellM;}
+
+  /** Get the current gas temperature inside the gas cell
+      @return gas temperature in Rankine. */
+  double GetTemperature(void) {return Temperature;}
+
+  /** Get the current gas pressure inside the gas cell
+      @return gas pressure in lbs / ft<sup>2</sup>. */
+  double GetPressure(void) {return Pressure;}
+
+private:
+
+  enum GasType {ttUNKNOWN, ttHYDROGEN, ttHELIUM, ttAIR};
+
+  GasType Type;
+  string type;
+  int CellNum;
+  // Structural constants
+  double MaxVolume;                 // [ft�]
+  double MaxOverpressure;           // [lbs/ft�]
+  FGColumnVector3 vXYZ;             // [in]
+  double Xradius, Yradius, Zradius; // [ft]
+  double Xwidth, Ywidth, Zwidth;    // [ft]
+  double ValveCoefficient;          // [ft^4 sec / slug]
+  typedef vector <FGFunction*> CoeffArray;
+  CoeffArray HeatTransferCoeff;
+  typedef vector <FGBallonet*> BallonetArray;
+  BallonetArray Ballonet;
+  // Variables
+  double Pressure;          // [lbs/ft�]
+  double Contents;          // [mol]
+  double Volume;            // [ft�]
+  double dVolumeIdeal;      // [ft�]
+  double Temperature;       // [Rankine]
+  double Buoyancy;          // [lbs] Note: Gross lift.
+                            // Does not include the weight of the gas itself.
+  double ValveOpen;         // 0 <= ValveOpen <= 1 (or higher).
+  double Mass;              // [slug]
+  FGMatrix33 gasCellJ;      // [slug foot�]
+  FGColumnVector3 gasCellM; // [lbs ft]
+
+  FGAuxiliary* Auxiliary;
+  FGAtmosphere* Atmosphere;
+  FGPropertyManager* PropertyManager;
+  FGInertial* Inertial;
+  FGMassBalance* MassBalance;
+  void Debug(int from);
+
+  /* Constants. */
+  const static double R;          // [lbs ft/(mol Rankine)]
+  const static double M_air;      // [slug/mol]
+  const static double M_hydrogen; // [slug/mol]
+  const static double M_helium;   // [slug/mol]
+
+  double M_gas() {                // [slug/mol]
+    switch (Type) {
+    case ttHYDROGEN:
+      return M_hydrogen;
+    case ttHELIUM:
+      return M_helium;
+    case ttAIR:
+      return M_air;
+    default:
+      return M_air;
+    }
+  }
+
+  double Cv_gas() {               // [??]
+    switch (Type) {
+    case ttHYDROGEN:
+      return 5.0/2.0;
+    case ttHELIUM:
+      return 3.0/2.0;
+    case ttAIR:
+      return 5.0/2.0;
+    default:
+      return 5.0/2.0;
+    }
+  }
+
+};
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+/** Models a ballonet inside a gas cell.
+    Models a ballonet inside a gas cell.
+    Not intended to be used outside FGGasCell.
+    See FGGasCell for the configuration file format.
+    @author Anders Gidenstam
+*/
+class FGBallonet : public FGJSBBase
+{
+public:
+  FGBallonet(FGFDMExec* exec, Element* el, int num, FGGasCell* parent);
+  ~FGBallonet();
+
+  /** Runs the ballonet model; called by FGGasCell
+   */
+  void Calculate(double dt);
+
+
+  /** Get the center of gravity location of the ballonet
+      @return CoG location in the structural frame. */
+  const FGColumnVector3& GetXYZ(void) {return vXYZ;}
+  /** Get the center of gravity location of the ballonet
+      @return CoG location in the structural frame. */
+  double GetXYZ(int idx) {return vXYZ(idx);}
+
+  /** Get the current mass of the ballonets
+      @return mass in slug. */
+  double GetMass(void) {return Contents * M_air;}
+
+  /** Get the moments of inertia of the ballonet
+      @return moments of inertia matrix in slug ft<sup>2</sup>. */
+  FGMatrix33& GetInertia(void) {return ballonetJ;}
+
+  /** Get the current volume of the ballonet
+      @return volume in ft<sup>3</sup>. */
+  double GetVolume(void) {return Volume;}
+  /** Get the current heat flow into the ballonet
+      @return heat flow in lbs ft / sec. */
+  double GetHeatFlow(void) {return dU;}             // [lbs ft / sec]
+
+private:
+  int CellNum;
+  // Structural constants
+  double MaxVolume;                 // [ft�]
+  double MaxOverpressure;           // [lbs/ft�]
+  FGColumnVector3 vXYZ;             // [in]
+  double Xradius, Yradius, Zradius; // [ft]
+  double Xwidth, Ywidth, Zwidth;    // [ft]
+  double ValveCoefficient;          // [ft^4 sec / slug]
+  typedef vector <FGFunction*> CoeffArray;
+  CoeffArray HeatTransferCoeff;     // [lbs ft / sec]
+  FGFunction* BlowerInput;          // [ft^3 / sec]
+  FGGasCell* Parent;
+  // Variables
+  double Pressure;         // [lbs/ft�]
+  double Contents;         // [mol]
+  double Volume;           // [ft�]
+  double dVolumeIdeal;     // [ft�]
+  double dU;               // [lbs ft / sec]
+  double Temperature;      // [Rankine]
+  double ValveOpen;        // 0 <= ValveOpen <= 1 (or higher).
+  FGMatrix33 ballonetJ;     // [slug foot�]
+
+  FGAuxiliary* Auxiliary;
+  FGAtmosphere* Atmosphere;
+  FGPropertyManager* PropertyManager;
+  FGInertial* Inertial;
+  void Debug(int from);
+
+  /* Constants. */
+  const static double R;          // [lbs ft/(mol Rankine)]
+  const static double M_air;      // [slug/mol]
+  const static double Cv_air;     // [??]
+};
+}
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+#endif
index c8bf6ab9e589ab85d0b19411692eda4ba0cf595b..f8067cfba3cfef786bd2b942f7338e69be902828 100644 (file)
@@ -64,15 +64,23 @@ FGGroundReactions::FGGroundReactions(FGFDMExec* fgex) : FGModel(fgex)
 
 FGGroundReactions::~FGGroundReactions(void)
 {
-  for (unsigned int i=0; i<lGear.size();i++) lGear[i].unbind();
+  for (unsigned int i=0; i<lGear.size();i++) delete lGear[i];
   lGear.clear();
 
-  unbind();
   Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGGroundReactions::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGGroundReactions::Run(void)
 {
   if (FGModel::Run()) return true;
@@ -81,19 +89,15 @@ bool FGGroundReactions::Run(void)
   vForces.InitMatrix();
   vMoments.InitMatrix();
 
-  if ( Propagate->GetDistanceAGL() < 300.0 ) { // Only execute gear code below 300 feet
-    vector <FGLGear>::iterator iGear = lGear.begin();
-
     // Sum forces and moments for all gear, here.
     // Some optimizations may be made here - or rather in the gear code itself.
     // The gear ::Run() method is called several times - once for each gear.
     // Perhaps there is some commonality for things which only need to be
     // calculated once.
-
-    while (iGear != lGear.end()) {
-      vForces  += iGear->Force();
-      vMoments += iGear->Moment();
-      iGear++;
+  if ( Propagate->GetDistanceAGL() < 300.0 ) { // Only execute gear code below 300 feet
+    for (unsigned int i=0; i<lGear.size(); i++) {
+      vForces  += lGear[i]->Force();
+      vMoments += lGear[i]->Moment();
     }
 
   }
@@ -107,7 +111,7 @@ bool FGGroundReactions::GetWOW(void)
 {
   bool result = false;
   for (unsigned int i=0; i<lGear.size(); i++) {
-    if (lGear[i].IsBogey() && lGear[i].GetWOW()) {
+    if (lGear[i]->IsBogey() && lGear[i]->GetWOW()) {
       result = true;
       break;
     }
@@ -125,12 +129,12 @@ bool FGGroundReactions::Load(Element* el)
 
   Element* contact_element = el->FindElement("contact");
   while (contact_element) {
-    lGear.push_back(FGLGear(contact_element, FDMExec, num++));
+    lGear.push_back(new FGLGear(contact_element, FDMExec, num++));
     FCS->AddGear(); // make the FCS aware of the landing gear
     contact_element = el->FindNextElement("contact");
   }
 
-  for (unsigned int i=0; i<lGear.size();i++) lGear[i].bind();
+  for (unsigned int i=0; i<lGear.size();i++) lGear[i]->bind();
 
   return true;
 }
@@ -142,8 +146,8 @@ string FGGroundReactions::GetGroundReactionStrings(string delimeter)
   std::ostringstream buf;
 
   for (unsigned int i=0;i<lGear.size();i++) {
-    if (lGear[i].IsBogey()) {
-      string name = lGear[i].GetName();
+    if (lGear[i]->IsBogey()) {
+      string name = lGear[i]->GetName();
       buf << name << " WOW" << delimeter
           << name << " stroke (ft)" << delimeter
           << name << " stroke velocity (ft/sec)" << delimeter
@@ -177,21 +181,21 @@ string FGGroundReactions::GetGroundReactionValues(string delimeter)
   std::ostringstream buf;
 
   for (unsigned int i=0;i<lGear.size();i++) {
-    if (lGear[i].IsBogey()) {
-      FGLGeargear = lGear[i];
-      buf << (gear.GetWOW() ? "1, " : "0, ")
-          << setprecision(5) << gear.GetCompLen() << delimeter
-          << setprecision(6) << gear.GetCompVel() << delimeter
-          << setprecision(10) << gear.GetCompForce() << delimeter
-          << gear.GetWheelSideForce() << delimeter
-          << gear.GetWheelRollForce() << delimeter
-          << gear.GetBodyXForce() << delimeter
-          << gear.GetBodyYForce() << delimeter
-          << setprecision(6) << gear.GetWheelVel(eX) << delimeter
-          << gear.GetWheelVel(eY) << delimeter
-          << gear.GetWheelRollVel() << delimeter
-          << gear.GetWheelSideVel() << delimeter
-          << gear.GetWheelSlipAngle() << delimeter;
+    if (lGear[i]->IsBogey()) {
+      FGLGear *gear = lGear[i];
+      buf << (gear->GetWOW() ? "1, " : "0, ")
+          << setprecision(5) << gear->GetCompLen() << delimeter
+          << setprecision(6) << gear->GetCompVel() << delimeter
+          << setprecision(10) << gear->GetCompForce() << delimeter
+          << gear->GetWheelSideForce() << delimeter
+          << gear->GetWheelRollForce() << delimeter
+          << gear->GetBodyXForce() << delimeter
+          << gear->GetBodyYForce() << delimeter
+          << setprecision(6) << gear->GetWheelVel(eX) << delimeter
+          << gear->GetWheelVel(eY) << delimeter
+          << gear->GetWheelRollVel() << delimeter
+          << gear->GetWheelSideVel() << delimeter
+          << gear->GetWheelSlipAngle() << delimeter;
     }
   }
 
@@ -219,19 +223,6 @@ void FGGroundReactions::bind(void)
   PropertyManager->Tie("forces/fbz-gear-lbs", this, eZ, (PMF)&FGGroundReactions::GetForces);
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGGroundReactions::unbind(void)
-{
-  PropertyManager->Untie("gear/num-units");
-  PropertyManager->Untie("moments/l-gear-lbsft");
-  PropertyManager->Untie("moments/m-gear-lbsft");
-  PropertyManager->Untie("moments/n-gear-lbsft");
-  PropertyManager->Untie("forces/fbx-gear-lbs");
-  PropertyManager->Untie("forces/fby-gear-lbs");
-  PropertyManager->Untie("forces/fbz-gear-lbs");
-}
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index 71d39e0e939b0d2f5ed7da1f3b4fbee43403191d..2a1b8e2424ebb08899b681b2c09164d01e244914 100644 (file)
@@ -66,7 +66,21 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Manages ground reactions modeling.
+/** Manages ground reactions modeling. Maintains a list of landing gear and
+    ground contact points, all instances of FGLGear.  Sums their forces and
+    moments so that these may be provided to FGPropagate.  Parses the 
+    \<ground_reactions> section of the aircraft configuration file.
+ <h3>Configuration File Format of \<ground_reactions> Section:</h3>
+@code
+    <ground_reactions>
+        <contact>
+           ... {see FGLGear for specifics of this format}
+        </contact>
+        ... {more contacts}
+    </ground_reactions>
+@endcode   
+
+
   */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -79,6 +93,7 @@ public:
   FGGroundReactions(FGFDMExec*);
   ~FGGroundReactions(void);
 
+  bool InitModel(void);
   bool Run(void);
   bool Load(Element* el);
   FGColumnVector3& GetForces(void) {return vForces;}
@@ -89,21 +104,19 @@ public:
   string GetGroundReactionValues(string delimeter);
   bool GetWOW(void);
 
-  int GetNumGearUnits(void) const { return lGear.size(); }
+  int GetNumGearUnits(void) const { return (int)lGear.size(); }
 
   /** Gets a gear instance
       @param gear index of gear instance
       @return a pointer to the FGLGear instance of the gear unit requested */
-  inline FGLGear* GetGearUnit(int gear) { return &(lGear[gear]); }
-
-  void bind(void);
-  void unbind(void);
+  inline FGLGear* GetGearUnit(int gear) { return lGear[gear]; }
 
 private:
-  vector <FGLGear> lGear;
+  vector <FGLGear*> lGear;
   FGColumnVector3 vForces;
   FGColumnVector3 vMoments;
 
+  void bind(void);
   void Debug(int from);
 };
 }
index e18098a44aaa2396c3c1c523076dfac3d3ab9c44..75a699f990689f73cbd9a9c1fe8fef835cc9141b 100644 (file)
@@ -55,12 +55,20 @@ FGInertial::FGInertial(FGFDMExec* fgex) : FGModel(fgex)
   Name = "FGInertial";
 
   // Defaults
-  RotationRate    = 0.00007272205217;
-  GM              = 14.06252720E15;
-  RadiusReference = 20925650.00;
+  RotationRate    = 0.00007292115;
+  GM              = 14.07644180E15;     // WGS84 value
+  RadiusReference = 20925650.00;        // Equatorial radius (WGS84)
+  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 
+  b               = 20855486.5951;      // WGS84 semiminor axis length in feet
+  earthPosAngle   = 0.0;
+
   gAccelReference = GM/(RadiusReference*RadiusReference);
   gAccel          = GM/(RadiusReference*RadiusReference);
 
+  bind();
+
   Debug(0);
 }
 
@@ -73,6 +81,17 @@ FGInertial::~FGInertial(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGInertial::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  earthPosAngle   = 0.0;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGInertial::Run(void)
 {
   // Fast return if we have nothing to do ...
@@ -82,10 +101,25 @@ bool FGInertial::Run(void)
   // Gravitation accel
   double r = Propagate->GetRadius();
   gAccel = GetGAccel(r);
+  earthPosAngle += State->Getdt()*RotationRate;
 
   return false;
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+double FGInertial::GetGAccel(double r) const
+{
+  return GM/(r*r);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGInertial::bind(void)
+{
+  PropertyManager->Tie("position/epa-rad", this, &FGInertial::GetEarthPositionAngle);
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index 72c7864c17dfb45b96b29552b0d449b6d2b349d7..03671d60b5319ad2819a43473ed409767ede7bb7 100644 (file)
@@ -68,7 +68,8 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Models inertial forces (e.g. centripetal and coriolis accelerations).
+/** Models inertial forces (e.g. centripetal and coriolis accelerations). Starting
+    conversion to WGS84.
   */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -81,19 +82,32 @@ public:
   FGInertial(FGFDMExec*);
   ~FGInertial(void);
 
+  bool InitModel(void);
+
   bool Run(void);
   double SLgravity(void) const {return gAccelReference;}
   double gravity(void) const {return gAccel;}
   double omega(void) const {return RotationRate;}
-  double GetGAccel(double r) const { return GM/(r*r); }
-  double RefRadius(void) const {return RadiusReference;}
+  double GetEarthPositionAngle(void) const { return earthPosAngle; }
+  double GetEarthPositionAngleDeg(void) const { return earthPosAngle*radtodeg;}
+  double GetGAccel(double r) const;
+  double GetRefRadius(void) const {return RadiusReference;}
+  double GetSemimajor(void) const {return a;}
+  double GetSemiminor(void) const {return b;}
 
 private:
   double gAccel;
   double gAccelReference;
   double RadiusReference;
   double RotationRate;
+  double earthPosAngle;
   double GM;
+  double C2_0; // WGS84 value for the C2,0 coefficient
+  double J2;   // WGS84 value for J2
+  double a;    // WGS84 semimajor axis length in feet 
+  double b;    // WGS84 semiminor axis length in feet
+
+  void bind(void);
   void Debug(int from);
 };
 }
index 412dd7c27b798846d32179532c3acbc50ad236a4..9c5c2259b9c743d4ec53b25bf01b5563a52d944f 100755 (executable)
@@ -73,6 +73,15 @@ FGInput::~FGInput()
   Debug(1);
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+bool FGInput::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //
 // This function handles accepting input commands from the socket interface.
@@ -206,6 +215,12 @@ bool FGInput::Load(Element* element)
   string name="", fname="";
   string property;
 
+  // if the input has already been set up, print a warning message and return
+  if (port > 0) {
+    cerr << "An input port has already been assigned for this run" << endl;
+    return false;
+  }
+
   port = int(element->GetAttributeValueAsNumber("port"));
   if (port == 0) {
     cerr << endl << "No port assigned in input element" << endl;
index 4ef5dad11f27de57251e9fc53828b8262696ce88..a20e741f8103c9987d400088172b227f61de3c93 100755 (executable)
@@ -73,7 +73,7 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Handles simulation input.
+/** Handles simulation socket input.
  */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -86,6 +86,7 @@ public:
   FGInput(FGFDMExec*);
   ~FGInput();
 
+  bool InitModel(void);
   bool Run(void);
 
   void SetType(string);
index b25b95a89aae7ff4e6fcc7692c43a3a6afcb5edd..a1e6b14ae03fade4334177496cb64d5642bf22c0 100644 (file)
@@ -69,6 +69,14 @@ FGLGear::FGLGear(Element* el, FGFDMExec* fdmex, int number) : Exec(fdmex),
 
   name = el->GetAttributeValue("name");
   sContactType = el->GetAttributeValue("type");
+  if (sContactType == "BOGEY") {
+    eContactType = ctBOGEY;
+  } else if (sContactType == "STRUCTURE") {
+    eContactType = ctSTRUCTURE;
+  } else {
+    eContactType = ctUNKNOWN;
+  }
+
   if (el->FindElement("spring_coeff"))
     kSpring = el->FindElementValueAsNumberConvertTo("spring_coeff", "LBS/FT");
   if (el->FindElement("damping_coeff"))
@@ -171,6 +179,8 @@ FGLGear::FGLGear(Element* el, FGFDMExec* fdmex, int number) : Exec(fdmex),
   
   GearUp = false;
   GearDown = true;
+  GearPos  = 1.0;
+  useFCSGearPos = false;
   Servicable = true;
 
 // Add some AI here to determine if gear is located properly according to its
@@ -266,6 +276,7 @@ FGLGear::FGLGear(const FGLGear& lgear)
   sSteerType      = lgear.sSteerType;
   sRetractable    = lgear.sRetractable;
   sContactType    = lgear.sContactType;
+  eContactType    = lgear.eContactType;
   sBrakeGroup     = lgear.sBrakeGroup;
   eSteerType      = lgear.eSteerType;
   eBrakeGrp       = lgear.eBrakeGrp;
@@ -273,6 +284,8 @@ FGLGear::FGLGear(const FGLGear& lgear)
   isRetractable   = lgear.isRetractable;
   GearUp          = lgear.GearUp;
   GearDown        = lgear.GearDown;
+  GearPos         = lgear.GearPos;
+  useFCSGearPos   = lgear.useFCSGearPos;
   WheelSlip       = lgear.WheelSlip;
   TirePressureNorm = lgear.TirePressureNorm;
   Servicable      = lgear.Servicable;
@@ -301,8 +314,6 @@ FGLGear::~FGLGear()
 
 FGColumnVector3& FGLGear::Force(void)
 {
-  FGColumnVector3 normal, cvel;
-  FGLocation contact, gearLoc;
   double t = Exec->GetState()->Getsim_time();
   dT = State->Getdt()*Exec->GetGroundReactions()->GetRate();
 
@@ -311,7 +322,7 @@ FGColumnVector3& FGLGear::Force(void)
 
   if (isRetractable) ComputeRetractionState();
 
-  if (GearUp) return vForce;
+  if (!GearDown) return vForce; // return the null vForce column vector
 
   vWhlBodyVec = MassBalance->StructuralToBody(vXYZ); // Get wheel in body frame
   vLocalGear = Propagate->GetTb2l() * vWhlBodyVec; // Get local frame wheel location
@@ -341,9 +352,8 @@ FGColumnVector3& FGLGear::Force(void)
 
     // Compute the forces in the wheel ground plane.
 
-    RollingForce = ((1.0 - TirePressureNorm) * 30
-                   + vLocalForce(eZ) * BrakeFCoeff) * (RollingWhlVel>=0?1.0:-1.0);
-
+    double sign = RollingWhlVel>0?1.0:(RollingWhlVel<0?-1.0:0.0);
+    RollingForce = ((1.0 - TirePressureNorm) * 30 + vLocalForce(eZ) * BrakeFCoeff) * sign;
     SideForce    = vLocalForce(eZ) * FCoeff;
 
     // Transform these forces back to the local reference frame.
@@ -400,13 +410,18 @@ FGColumnVector3& FGLGear::Force(void)
     compressLength = 0.0;
 
     // Return to neutral position between 1.0 and 0.8 gear pos.
-    SteerAngle *= max(FCS->GetGearPos()-0.8, 0.0)/0.2;
+    SteerAngle *= max(GetGearUnitPos()-0.8, 0.0)/0.2;
 
     ResetReporting();
   }
 
   ReportTakeoffOrLanding();
-  CrashDetect();
+
+  // Require both WOW and LastWOW to be true before checking crash conditions
+  // to allow the WOW flag to be used in terminating a scripted run.
+  if (WOW && lastWOW) CrashDetect();
+
+  lastWOW = WOW;
 
   return vForce;
 }
@@ -415,10 +430,11 @@ FGColumnVector3& FGLGear::Force(void)
 
 void FGLGear::ComputeRetractionState(void)
 {
-  if (FCS->GetGearPos() < 0.01) {
+  double gearPos = GetGearUnitPos();
+  if (gearPos < 0.01) {
     GearUp   = true;
     GearDown = false;
-  } else if (FCS->GetGearPos() > 0.99) {
+  } else if (gearPos > 0.99) {
     GearDown = true;
     GearUp   = false;
   } else {
@@ -460,6 +476,9 @@ void FGLGear::ComputeSlipAngle(void)
 
 void FGLGear::ComputeSteeringAngle(void)
 {
+  double casterLocalFrameAngleRad = 0.0;
+  double casterAngle = 0.0;
+
   switch (eSteerType) {
   case stSteer:
     SteerAngle = degtorad * FCS->GetSteerPosDeg(GearNumber);
@@ -472,6 +491,8 @@ void FGLGear::ComputeSteeringAngle(void)
     // to the actual velocity vector of the wheel, given aircraft velocity vector
     // and omega.
     SteerAngle = 0.0;
+    casterLocalFrameAngleRad = acos(vWhlVelVec(eX)/vWhlVelVec.Magnitude());
+    casterAngle = casterLocalFrameAngleRad - Propagate->GetEuler(ePsi);
     break;
   default:
     cerr << "Improper steering type membership detected for this gear." << endl;
@@ -491,6 +512,7 @@ void FGLGear::ResetReporting(void)
     FirstContact = false;
     StartedGroundRun = false;
     LandingReported = false;
+    TakeoffReported = true;
     LandingDistanceTraveled = 0.0;
     MaximumStrutForce = MaximumStrutTravel = 0.0;
   }
@@ -515,7 +537,7 @@ void FGLGear::InitializeReporting(void)
   if ((Propagate->GetVel().Magnitude() > 0.1) &&
       (FCS->GetBrake(bgLeft) == 0) &&
       (FCS->GetBrake(bgRight) == 0) &&
-      (FCS->GetThrottlePos(0) == 1) && !StartedGroundRun)
+      (FCS->GetThrottlePos(0) > 0.90) && !StartedGroundRun)
   {
     TakeoffDistanceTraveled = 0;
     TakeoffDistanceTraveled50ft = 0;
@@ -530,25 +552,31 @@ void FGLGear::ReportTakeoffOrLanding(void)
 {
   double deltaT = State->Getdt()*Exec->GetGroundReactions()->GetRate();
 
-  if (FirstContact) LandingDistanceTraveled += Auxiliary->GetVground()*deltaT;
+  if (FirstContact)
+    LandingDistanceTraveled += Auxiliary->GetVground()*deltaT;
 
   if (StartedGroundRun) {
      TakeoffDistanceTraveled50ft += Auxiliary->GetVground()*deltaT;
     if (WOW) TakeoffDistanceTraveled += Auxiliary->GetVground()*deltaT;
   }
 
-  if (ReportEnable && Auxiliary->GetVground() <= 0.05 && !LandingReported) {
+  if ( ReportEnable
+       && Auxiliary->GetVground() <= 0.05
+       && !LandingReported
+       && Exec->GetGroundReactions()->GetWOW())
+  {
     if (debug_lvl > 0) Report(erLand);
   }
 
-  if (ReportEnable && !TakeoffReported &&
-     (vLocalGear(eZ) - Propagate->GetDistanceAGL()) < -50.0)
+  if ( ReportEnable
+       && !TakeoffReported
+       && (Propagate->GetDistanceAGL() - vLocalGear(eZ)) > 50.0
+       && !Exec->GetGroundReactions()->GetWOW())
   {
     if (debug_lvl > 0) Report(erTakeoff);
   }
 
   if (lastWOW != WOW) PutMessage("GEAR_CONTACT: " + name, WOW);
-  lastWOW = WOW;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -659,20 +687,38 @@ void FGLGear::ComputeVerticalStrutForce(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGLGear::bind(void)
+double FGLGear::GetGearUnitPos(void)
 {
-  char property_name[80];
-  snprintf(property_name, 80, "gear/unit[%d]/slip-angle-deg", GearNumber);
-  Exec->GetPropertyManager()->Tie( property_name, &WheelSlip );
+  // hack to provide backward compatibility to gear/gear-pos-norm property
+  if( useFCSGearPos || FCS->GetGearPos() != 1.0 ) {
+    useFCSGearPos = true;
+    return FCS->GetGearPos();
+  }
+  return GearPos;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGLGear::unbind(void)
+void FGLGear::bind(void)
 {
   char property_name[80];
-  snprintf(property_name, 80, "gear/unit[%d]/slip-angle-deg", GearNumber);
-  Exec->GetPropertyManager()->Untie( property_name );
+  if (eContactType == ctBOGEY) {
+    snprintf(property_name, 80, "gear/unit[%d]/slip-angle-deg", GearNumber);
+    Exec->GetPropertyManager()->Tie( property_name, &WheelSlip );
+    snprintf(property_name, 80, "gear/unit[%d]/WOW", GearNumber);
+    Exec->GetPropertyManager()->Tie( property_name, &WOW );
+    snprintf(property_name, 80, "gear/unit[%d]/wheel-speed-fps", GearNumber);
+    Exec->GetPropertyManager()->Tie( property_name, &RollingWhlVel );
+    snprintf(property_name, 80, "gear/unit[%d]/z-position", GearNumber);
+    Exec->GetPropertyManager()->Tie( property_name, (FGLGear*)this,
+                          &FGLGear::GetZPosition, &FGLGear::SetZPosition);
+  }
+
+  if( isRetractable ) {
+    snprintf(property_name, 80, "gear/unit[%d]/pos-norm", GearNumber);
+    Exec->GetPropertyManager()->Tie( property_name, &GearPos );
+  }
+
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -736,7 +782,7 @@ void FGLGear::Debug(int from)
       cout << "      Damping Constant: " << bDamp         << endl;
       cout << "      Dynamic Friction: " << dynamicFCoeff << endl;
       cout << "      Static Friction:  " << staticFCoeff  << endl;
-      if (sContactType == "BOGEY") {
+      if (eContactType == ctBOGEY) {
         cout << "      Rolling Friction: " << rollingFCoeff << endl;
         cout << "      Steering Type:    " << sSteerType    << endl;
         cout << "      Grouping:         " << sBrakeGroup   << endl;
index fdfa809c9d7b7590bc7091ff2bcf17bae229b17c..8fe0bb20f63dacc409b43813aeb9140957dddfb2 100644 (file)
@@ -78,7 +78,7 @@ CLASS DOCUMENTATION
     are the parameters that can be specified in the config file for modeling
     landing gear:
     <p>
-    <b><u>Physical Characteristics</u></b><br>
+    <h3>Physical Characteristics</h3>
     <ol>
     <li>X, Y, Z location, in inches in structural coordinate frame</li>
     <li>Spring constant, in lbs/ft</li>
@@ -86,7 +86,7 @@ CLASS DOCUMENTATION
     <li>Dynamic Friction Coefficient</li>
     <li>Static Friction Coefficient</li>
     </ol></p><p>
-    <b><u>Operational Properties</b></u><br>
+    <h3>Operational Properties</h3>
     <ol>
     <li>Name</li>
     <li>Steerability attribute {one of STEERABLE | FIXED | CASTERED}</li>
@@ -94,7 +94,7 @@ CLASS DOCUMENTATION
     <li>Max Steer Angle, in degrees</li>
     </ol></p>
     <p>
-    <b><u>Algorithm and Approach to Modeling</u></b><br>
+    <h3>Algorithm and Approach to Modeling</h3>
     <ol>
     <li>Find the location of the uncompressed landing gear relative to the CG of
     the aircraft. Remember, the structural coordinate frame that the aircraft is
@@ -158,6 +158,37 @@ CLASS DOCUMENTATION
     (radius to wheel crossed into the wheel force). Both of these operands are
     in body frame.</li>
     </ol>
+
+    <h3>Configuration File Format:</h3>
+@code
+        <contact type="{BOGEY | STRUCTURE}" name="{string}">
+            <location unit="{IN | M}">
+                <x> {number} </x>
+                <y> {number} </y>
+                <z> {number} </z>
+            </location>
+            <static_friction> {number} </static_friction>
+            <dynamic_friction> {number} </dynamic_friction>
+            <rolling_friction> {number} </rolling_friction>
+            <spring_coeff unit="{LBS/FT | N/M}"> {number} </spring_coeff>
+            <damping_coeff unit="{LBS/FT/SEC | N/M/SEC}"> {number} </damping_coeff>
+            <damping_coeff_rebound unit="{LBS/FT/SEC | N/M/SEC}"> {number} </damping_coeff_rebound>
+            <max_steer unit="DEG"> {number | 0 | 360} </max_steer>
+            <brake_group> {NONE | LEFT | RIGHT | CENTER | NOSE | TAIL} </brake_group>
+            <retractable>{0 | 1}</retractable>
+            <table type="{CORNERING_COEFF}">
+            </table>
+            <relaxation_velocity>
+               <rolling unit="{FT/SEC | KTS | M/S}"> {number} </rolling>
+               <side unit="{FT/SEC | KTS | M/S}"> {number} </side>
+            </relaxation_velocity>
+            <force_lag_filter>
+               <rolling> {number} </rolling>
+               <side> {number} </side>
+            </force_lag_filter>
+            <wheel_slip_filter> {number} </wheel_slip_filter>  
+        </contact>
+@endcode
     @author Jon S. Berndt
     @version $Id$
     @see Richard E. McFarland, "A Standard Kinematic Model for Flight Simulation at
@@ -179,12 +210,15 @@ public:
   enum BrakeGroup {bgNone=0, bgLeft, bgRight, bgCenter, bgNose, bgTail };
   /// Steering group membership enumerators
   enum SteerType {stSteer, stFixed, stCaster};
+  /// Contact point type
+  enum ContactType {ctBOGEY, ctSTRUCTURE, ctUNKNOWN};
   /// Report type enumerators
   enum ReportType {erNone=0, erTakeoff, erLand};
   /** Constructor
       @param el a pointer to the XML element that contains the CONTACT info.
       @param Executive a pointer to the parent executive object
-      @param File a pointer to the config file instance */
+      @param number integer identifier for this instance of FGLGear
+  */
   FGLGear(Element* el, FGFDMExec* Executive, int number);
   /** Constructor
       @param lgear a reference to an existing FGLGear object     */
@@ -200,25 +234,25 @@ public:
 
   /// Gets the location of the gear in Body axes
   FGColumnVector3& GetBodyLocation(void) { return vWhlBodyVec; }
-  double GetBodyLocation(int idx) { return vWhlBodyVec(idx); }
+  double GetBodyLocation(int idx) const { return vWhlBodyVec(idx); }
 
   FGColumnVector3& GetLocalGear(void) { return vLocalGear; }
-  double GetLocalGear(int idx) { return vLocalGear(idx); }
+  double GetLocalGear(int idx) const { return vLocalGear(idx); }
 
   /// Gets the name of the gear
-  inline string GetName(void)      {return name;          }
+  inline string GetName(void) const {return name;          }
   /// Gets the Weight On Wheels flag value
-  inline bool   GetWOW(void)       {return WOW;           }
+  inline bool   GetWOW(void) const {return WOW;           }
   /// Gets the current compressed length of the gear in feet
-  inline double  GetCompLen(void)   {return compressLength;}
+  inline double  GetCompLen(void) const {return compressLength;}
   /// Gets the current gear compression velocity in ft/sec
-  inline double  GetCompVel(void)   {return compressSpeed; }
+  inline double  GetCompVel(void) const {return compressSpeed; }
   /// Gets the gear compression force in pounds
-  inline double  GetCompForce(void) {return Force()(3);    }
-  inline double  GetBrakeFCoeff(void) {return BrakeFCoeff;}
+  inline double  GetCompForce(void) const {return vForce(eZ);    }
+  inline double  GetBrakeFCoeff(void) const {return BrakeFCoeff;}
 
   /// Gets the current normalized tire pressure
-  inline double  GetTirePressure(void) { return TirePressureNorm; }
+  inline double  GetTirePressure(void) const { return TirePressureNorm; }
   /// Sets the new normalized tire pressure
   inline void    SetTirePressure(double p) { TirePressureNorm = p; }
 
@@ -230,31 +264,33 @@ public:
   inline void SetReport(bool flag) { ReportEnable = flag; }
   /** Get the console touchdown reporting feature
       @return true if reporting is turned on */
-  inline bool GetReport(void)    { return ReportEnable; }
-  double GetSteerNorm(void) const { return radtodeg/maxSteerAngle*SteerAngle; }
+  inline bool GetReport(void) const  { return ReportEnable; }
+  double GetSteerNorm(void) const    { return radtodeg/maxSteerAngle*SteerAngle; }
   double GetDefaultSteerAngle(double cmd) const { return cmd*maxSteerAngle; }
-  double GetstaticFCoeff(void) { return staticFCoeff; }
+  double GetstaticFCoeff(void) const { return staticFCoeff; }
+
+  inline int GetBrakeGroup(void) const { return (int)eBrakeGrp; }
+  inline int GetSteerType(void) const  { return (int)eSteerType; }
 
-  inline int GetBrakeGroup(void) { return (int)eBrakeGrp; }
-  inline int GetSteerType(void)  { return (int)eSteerType; }
+  inline double GetZPosition(void) const { return vXYZ(3); }
+  inline void SetZPosition(double z) { vXYZ(3) = z; }
 
   bool GetSteerable(void) const { return eSteerType != stFixed; }
-  inline bool GetRetractable(void)         { return isRetractable;   }
-  inline bool GetGearUnitUp(void)          { return GearUp;          }
-  inline bool GetGearUnitDown(void)        { return GearDown;        }
-  inline double GetWheelSideForce(void)    { return SideForce;       }
-  inline double GetWheelRollForce(void)    { return RollingForce;    }
-  inline double GetWheelSideVel(void)      { return SideWhlVel;      }
-  inline double GetWheelRollVel(void)      { return RollingWhlVel;   }
-  inline double GetBodyXForce(void)        { return vLocalForce(eX); }
-  inline double GetBodyYForce(void)        { return vLocalForce(eY); }
-  inline double GetWheelSlipAngle(void)    { return WheelSlip;       }
-  double GetWheelVel(int axis)             { return vWhlVelVec(axis);}
-
-  bool IsBogey(void) {return (sContactType == string("BOGEY"));}
+  inline bool GetRetractable(void) const      { return isRetractable;   }
+  inline bool GetGearUnitUp(void) const       { return GearUp;          }
+  inline bool GetGearUnitDown(void) const     { return GearDown;        }
+  inline double GetWheelSideForce(void) const { return SideForce;       }
+  inline double GetWheelRollForce(void) const { return RollingForce;    }
+  inline double GetWheelSideVel(void) const   { return SideWhlVel;      }
+  inline double GetWheelRollVel(void) const   { return RollingWhlVel;   }
+  inline double GetBodyXForce(void) const     { return vLocalForce(eX); }
+  inline double GetBodyYForce(void) const     { return vLocalForce(eY); }
+  inline double GetWheelSlipAngle(void) const { return WheelSlip;       }
+  double GetWheelVel(int axis) const          { return vWhlVelVec(axis);}
+  bool IsBogey(void) const                    { return (eContactType == ctBOGEY);}
+  double GetGearUnitPos(void);
 
   void bind(void);
-  void unbind(void);
 
 private:
   int GearNumber;
@@ -266,7 +302,9 @@ private:
   FGColumnVector3 last_vForce; // remove this
   FGColumnVector3 vLocalForce;
   FGColumnVector3 vWhlVelVec;     // Velocity of this wheel (Local)
+  FGColumnVector3 normal, cvel;
   FGColumnVector3 prevOut, prevIn;
+  FGLocation contact, gearLoc;
   FGTable *ForceY_Table;
   double dT;
   double SteerAngle;
@@ -293,6 +331,8 @@ private:
   double prevSlipOut;
   double TirePressureNorm;
   double SinWheel, CosWheel;
+  double GearPos;
+  bool   useFCSGearPos;
   bool WOW;
   bool lastWOW;
   bool FirstContact;
@@ -309,8 +349,9 @@ private:
   string sRetractable;
   string sContactType;
 
-  BrakeGroup eBrakeGrp;
-  SteerType  eSteerType;
+  BrakeGroup  eBrakeGrp;
+  ContactType eContactType;
+  SteerType   eSteerType;
   double  maxSteerAngle;
   double RFRV;  // Rolling force relaxation velocity
   double SFRV;  // Side force relaxation velocity
index f39e97a65cb1eef8839af06a097973d6525ab9eb..69c3a67230064b9d5c945b28728f239e507de1ef 100644 (file)
@@ -40,6 +40,7 @@ INCLUDES
 
 #include "FGMassBalance.h"
 #include "FGPropulsion.h"
+#include "FGBuoyantForces.h"
 #include <input_output/FGPropertyManager.h>
 
 namespace JSBSim {
@@ -72,13 +73,23 @@ FGMassBalance::FGMassBalance(FGFDMExec* fdmex) : FGModel(fdmex)
 
 FGMassBalance::~FGMassBalance()
 {
-  unbind();
+  for (unsigned int i=0; i<PointMasses.size(); i++) delete PointMasses[i];
   PointMasses.clear();
+
   Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGMassBalance::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGMassBalance::Load(Element* el)
 {
   Element *element;
@@ -98,9 +109,9 @@ bool FGMassBalance::Load(Element* el)
     bixz = el->FindElementValueAsNumberConvertTo("ixz", "SLUG*FT2");
   if (el->FindElement("iyz"))
     biyz = el->FindElementValueAsNumberConvertTo("iyz", "SLUG*FT2");
-  SetAircraftBaseInertias(FGMatrix33(  bixx,  -bixy,  -bixz,
+  SetAircraftBaseInertias(FGMatrix33(  bixx,  -bixy,  bixz,
                                       -bixy,  biyy,  -biyz,
-                                      -bixz,  -biyz,  bizz ));
+                                       bixz,  -biyz,  bizz ));
   EmptyWeight = el->FindElementValueAsNumberConvertTo("emptywt", "LBS");
 
   element = el->FindElement("location");
@@ -133,14 +144,16 @@ bool FGMassBalance::Run(void)
   if (FGModel::Run()) return true;
   if (FDMExec->Holding()) return false;
 
-  Weight = EmptyWeight + Propulsion->GetTanksWeight() + GetPointMassWeight();
+  Weight = EmptyWeight + Propulsion->GetTanksWeight() + GetPointMassWeight()
+    + BuoyantForces->GetGasMass()*slugtolb;
 
   Mass = lbtoslug*Weight;
 
 // Calculate new CG
 
   vXYZcg = (Propulsion->GetTanksMoment() + EmptyWeight*vbaseXYZcg
-                                     + GetPointMassMoment() ) / Weight;
+            + GetPointMassMoment()
+            + BuoyantForces->GetGasMassMoment()) / Weight;
 
 // Calculate new total moments of inertia
 
@@ -151,6 +164,7 @@ bool FGMassBalance::Run(void)
   // Then add the contributions from the additional pointmasses.
   mJ += CalculatePMInertias();
   mJ += Propulsion->CalculateTankInertias();
+  mJ += BuoyantForces->GetGasMassInertia();
 
   Ixx = mJ(1,1);
   Iyy = mJ(2,2);
@@ -186,6 +200,8 @@ bool FGMassBalance::Run(void)
 
 void FGMassBalance::AddPointMass(Element* el)
 {
+  char tmp[80];
+
   Element* loc_element = el->FindElement("location");
   string pointmass_name = el->GetAttributeValue("name");
   if (!loc_element) {
@@ -195,7 +211,13 @@ void FGMassBalance::AddPointMass(Element* el)
 
   double w = el->FindElementValueAsNumberConvertTo("weight", "LBS");
   FGColumnVector3 vXYZ = loc_element->FindElementTripletConvertTo("IN");
-  PointMasses.push_back(PointMass(w, vXYZ));
+  PointMasses.push_back(new PointMass(w, vXYZ));
+
+  int num = PointMasses.size()-1;
+
+  snprintf(tmp, 80, "inertia/pointmass-weight-lbs[%u]", num);
+  PropertyManager->Tie( tmp, this, num, &FGMassBalance::GetPointMassWeight,
+                                        &FGMassBalance::SetPointMassWeight);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -205,7 +227,7 @@ double FGMassBalance::GetPointMassWeight(void)
   double PM_total_weight = 0.0;
 
   for (unsigned int i=0; i<PointMasses.size(); i++) {
-    PM_total_weight += PointMasses[i].Weight;
+    PM_total_weight += PointMasses[i]->Weight;
   }
   return PM_total_weight;
 }
@@ -217,7 +239,7 @@ FGColumnVector3& FGMassBalance::GetPointMassMoment(void)
   PointMassCG.InitMatrix();
 
   for (unsigned int i=0; i<PointMasses.size(); i++) {
-    PointMassCG += PointMasses[i].Weight*PointMasses[i].Location;
+    PointMassCG += PointMasses[i]->Weight*PointMasses[i]->Location;
   }
   return PointMassCG;
 }
@@ -234,7 +256,7 @@ FGMatrix33& FGMassBalance::CalculatePMInertias(void)
   pmJ = FGMatrix33();
 
   for (unsigned int i=0; i<size; i++)
-    pmJ += GetPointmassInertia( lbtoslug * PointMasses[i].Weight, PointMasses[i].Location );
+    pmJ += GetPointmassInertia( lbtoslug * PointMasses[i]->Weight, PointMasses[i]->Location );
 
   return pmJ;
 }
@@ -281,6 +303,8 @@ void FGMassBalance::bind(void)
                        &FGMassBalance::GetMass);
   PropertyManager->Tie("inertia/weight-lbs", this,
                        &FGMassBalance::GetWeight);
+  PropertyManager->Tie("inertia/empty-weight-lbs", this,
+    &FGMassBalance::GetWeight, &FGMassBalance::SetEmptyWeight);
   PropertyManager->Tie("inertia/cg-x-in", this,1,
                        (PMF)&FGMassBalance::GetXYZcg);
   PropertyManager->Tie("inertia/cg-y-in", this,2,
@@ -289,17 +313,6 @@ void FGMassBalance::bind(void)
                        (PMF)&FGMassBalance::GetXYZcg);
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGMassBalance::unbind(void)
-{
-  PropertyManager->Untie("inertia/mass-slugs");
-  PropertyManager->Untie("inertia/weight-lbs");
-  PropertyManager->Untie("inertia/cg-x-in");
-  PropertyManager->Untie("inertia/cg-y-in");
-  PropertyManager->Untie("inertia/cg-z-in");
-}
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
@@ -336,10 +349,10 @@ void FGMassBalance::Debug(int from)
       cout << "    CG (x, y, z): " << vbaseXYZcg << endl;
       // ToDo: Need to add point mass outputs here
       for (unsigned int i=0; i<PointMasses.size(); i++) {
-        cout << "    Point Mass Object: " << PointMasses[i].Weight << " lbs. at "
-                   << "X, Y, Z (in.): " << PointMasses[i].Location(eX) << "  "
-                   << PointMasses[i].Location(eY) << "  "
-                   << PointMasses[i].Location(eZ) << endl;
+        cout << "    Point Mass Object: " << PointMasses[i]->Weight << " lbs. at "
+                   << "X, Y, Z (in.): " << PointMasses[i]->Location(eX) << "  "
+                   << PointMasses[i]->Location(eY) << "  "
+                   << PointMasses[i]->Location(eZ) << endl;
       }
     }
   }
index 13f1aa9b370a003854e5efb120a29475c88e3010..b3008b28356eec26044287d124a4c709f21ccc90 100644 (file)
@@ -60,7 +60,36 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Models weight and balance information.
+/** Models weight, balance and moment of inertia information.  Maintains a vector
+    of point masses. Sums the contribution of all, and provides this to FGPropagate.
+    Loads the \<mass_balance> section of the aircraft configuration file.
+
+    <h3>Configuration File Format:</h3>
+@code
+    <mass_balance>
+        <ixx unit="{SLUG*FT2 | KG*M2}"> {number} </ixx>
+        <iyy unit="{SLUG*FT2 | KG*M2}"> {number} </iyy>
+        <izz unit="{SLUG*FT2 | KG*M2}"> {number} </izz>
+        <ixy unit="{SLUG*FT2 | KG*M2}"> {number} </ixy>
+        <ixz unit="{SLUG*FT2 | KG*M2}"> {number} </ixz>
+        <iyz unit="{SLUG*FT2 | KG*M2}"> {number} </iyz>
+        <emptywt unit="{LBS | KG"> {number} </emptywt>
+        <location name="CG" unit="{IN | M}">
+            <x> {number} </x>
+            <y> {number} </y>
+            <z> {number} </z>
+        </location>
+        <pointmass name="{string}">
+            <weight unit="{LBS | KG}"> {number} </weight>
+            <location name="POINTMASS" unit="{IN | M}">
+                <x> {number} </x>
+                <y> {number} </y>
+                <z> {number} </z>
+            </location>
+        </pointmass>
+        ... other point masses ...
+    </mass_balance>
+@endcode
   */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -75,7 +104,7 @@ public:
   ~FGMassBalance();
 
   bool Load(Element* el);
-
+  bool InitModel(void);
   bool Run(void);
 
   inline double GetMass(void) const {return Mass;}
@@ -122,14 +151,22 @@ public:
 
   void AddPointMass(Element* el);
   double GetPointMassWeight(void);
+  double GetPointMassWeight(int idx) const {
+    if (idx < (int)PointMasses.size()) return(PointMasses[idx]->Weight);
+    else return 0.0;
+  }
+
+  void SetPointMassWeight(int idx, double pmw) {
+    if (idx < (int)PointMasses.size()) {
+      PointMasses[idx]->Weight = pmw;
+    }
+  }
+
   FGColumnVector3& GetPointMassMoment(void);
   FGMatrix33& GetJ(void) {return mJ;}
   FGMatrix33& GetJinv(void) {return mJinv;}
   void SetAircraftBaseInertias(FGMatrix33 BaseJ) {baseJ = BaseJ;}
 
-  void bind(void);
-  void unbind(void);
-
 private:
   double Weight;
   double EmptyWeight;
@@ -154,8 +191,9 @@ private:
     double Weight;
   };
 
-  vector <struct PointMass> PointMasses;
+  vector <struct PointMass*> PointMasses;
 
+  void bind(void);
   void Debug(int from);
 };
 }
index 778d2b3a37717d900eb61581d4ddaa8da704f31f..651f301eac300cd725f193a8ad5decede9f97602 100644 (file)
@@ -48,6 +48,7 @@ INCLUDES
 #include "FGAerodynamics.h"
 #include "FGInertial.h"
 #include "FGGroundReactions.h"
+#include "FGExternalReactions.h"
 #include "FGAircraft.h"
 #include "FGPropagate.h"
 #include "FGAuxiliary.h"
@@ -78,6 +79,7 @@ FGModel::FGModel(FGFDMExec* fdmex)
   Aerodynamics    = 0;
   Inertial        = 0;
   GroundReactions = 0;
+  ExternalReactions = 0;
   Aircraft        = 0;
   Propagate       = 0;
   Auxiliary       = 0;
@@ -112,6 +114,8 @@ bool FGModel::InitModel(void)
   Aerodynamics    = FDMExec->GetAerodynamics();
   Inertial        = FDMExec->GetInertial();
   GroundReactions = FDMExec->GetGroundReactions();
+  ExternalReactions = FDMExec->GetExternalReactions();
+  BuoyantForces   = FDMExec->GetBuoyantForces();
   Aircraft        = FDMExec->GetAircraft();
   Propagate       = FDMExec->GetPropagate();
   Auxiliary       = FDMExec->GetAuxiliary();
@@ -124,6 +128,7 @@ bool FGModel::InitModel(void)
       !Aerodynamics ||
       !Inertial ||
       !GroundReactions ||
+      !ExternalReactions ||
       !Aircraft ||
       !Propagate ||
       !Auxiliary) return(false);
index 4d0f8b7f261f78515df373b1194dfce390abb55c..3260d22cc76d579cf18e83cc05e1c4214d8796a4 100644 (file)
@@ -82,6 +82,8 @@ class FGMassBalance;
 class FGAerodynamics;
 class FGInertial;
 class FGGroundReactions;
+class FGExternalReactions;
+class FGBuoyantForces;
 class FGAircraft;
 class FGPropagate;
 class FGAuxiliary;
@@ -140,6 +142,8 @@ protected:
   FGAerodynamics*    Aerodynamics;
   FGInertial*        Inertial;
   FGGroundReactions* GroundReactions;
+  FGExternalReactions* ExternalReactions;
+  FGBuoyantForces*   BuoyantForces;
   FGAircraft*        Aircraft;
   FGPropagate*       Propagate;
   FGAuxiliary*       Auxiliary;
index 64aaf018f0195d888615fb1d8142933049594317..18fa12e122f51c3c6406cdb46a89b865c5decea3 100644 (file)
@@ -33,6 +33,7 @@ later.
 HISTORY
 --------------------------------------------------------------------------------
 12/02/98   JSB   Created
+11/09/07   HDW   Added FlightGear Socket Interface
 
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 INCLUDES
@@ -50,15 +51,71 @@ INCLUDES
 #include "FGPropagate.h"
 #include "FGAuxiliary.h"
 #include "FGInertial.h"
-
+#include "FGPropulsion.h"   //access to FGEngine, FGTank
+#include "models/propulsion/FGPiston.h"
 #include <fstream>
 #include <iomanip>
 
+#include "input_output/net_fdm.hxx"
+
+#if defined(WIN32) && !defined(__CYGWIN__)
+#  include <windows.h>
+#else
+#  include <netinet/in.h>       // htonl() ntohl()
+#endif
+
+static const int endianTest = 1;
+#define isLittleEndian (*((char *) &endianTest ) != 0)
+
+
 namespace JSBSim {
 
 static const char *IdSrc = "$Id$";
 static const char *IdHdr = ID_OUTPUT;
 
+// (stolen from FGFS native_fdm.cxx)
+// The function htond is defined this way due to the way some
+// processors and OSes treat floating point values.  Some will raise
+// an exception whenever a "bad" floating point value is loaded into a
+// floating point register.  Solaris is notorious for this, but then
+// so is LynxOS on the PowerPC.  By translating the data in place,
+// there is no need to load a FP register with the "corruped" floating
+// point value.  By doing the BIG_ENDIAN test, I can optimize the
+// routine for big-endian processors so it can be as efficient as
+// possible
+static void htond (double &x)
+{
+    if ( isLittleEndian ) {
+        int    *Double_Overlay;
+        int     Holding_Buffer;
+
+        Double_Overlay = (int *) &x;
+        Holding_Buffer = Double_Overlay [0];
+
+        Double_Overlay [0] = htonl (Double_Overlay [1]);
+        Double_Overlay [1] = htonl (Holding_Buffer);
+    } else {
+        return;
+    }
+}
+
+// Float version
+static void htonf (float &x)
+{
+    if ( isLittleEndian ) {
+        int    *Float_Overlay;
+        int     Holding_Buffer;
+
+        Float_Overlay = (int *) &x;
+        Holding_Buffer = Float_Overlay [0];
+
+        Float_Overlay [0] = htonl (Holding_Buffer);
+    } else {
+        return;
+    }
+}
+
+
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 CLASS IMPLEMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
@@ -68,12 +125,16 @@ FGOutput::FGOutput(FGFDMExec* fdmex) : FGModel(fdmex)
   Name = "FGOutput";
   sFirstPass = dFirstPass = true;
   socket = 0;
+  flightGearSocket = 0;
   Type = otNone;
   SubSystems = 0;
   enabled = true;
   delimeter = ", ";
   Filename = "";
   DirectivesFile = "";
+  output_file_name = "";
+
+  memset(&fgSockBuf, 0x00, sizeof(fgSockBuf));
 
   Debug(0);
 }
@@ -83,12 +144,22 @@ FGOutput::FGOutput(FGFDMExec* fdmex) : FGModel(fdmex)
 FGOutput::~FGOutput()
 {
   delete socket;
+  delete flightGearSocket;
   OutputProperties.clear();
   Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGOutput::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGOutput::Run(void)
 {
   if (FGModel::Run()) return true;
@@ -96,6 +167,8 @@ bool FGOutput::Run(void)
   if (enabled && !State->IntegrationSuspended()&& !FDMExec->Holding()) {
     if (Type == otSocket) {
       SocketOutput();
+    } else if (Type == otFlightGear) {
+      FlightGearSocketOutput();
     } else if (Type == otCSV || Type == otTab) {
       DelimitedOutput(Filename);
     } else if (Type == otTerminal) {
@@ -121,6 +194,8 @@ void FGOutput::SetType(string type)
     delimeter = "\t";
   } else if (type == "SOCKET") {
     Type = otSocket;
+  } else if (type == "FLIGHTGEAR") {
+    Type = otFlightGear;
   } else if (type == "TERMINAL") {
     Type = otTerminal;
   } else if (type != string("NONE")) {
@@ -173,6 +248,7 @@ void FGOutput::DelimitedOutput(string fname)
       outstream << delimeter;
       outstream << "q bar (psf)" + delimeter;
       outstream << "V_{Total} (ft/s)" + delimeter;
+      outstream << "V_{Inertial} (ft/s)" + delimeter;
       outstream << "UBody" + delimeter + "VBody" + delimeter + "WBody" + delimeter;
       outstream << "Aero V_{X Body} (ft/s)" + delimeter + "Aero V_{Y Body} (ft/s)" + delimeter + "Aero V_{Z Body} (ft/s)" + delimeter;
       outstream << "V_{North} (ft/s)" + delimeter + "V_{East} (ft/s)" + delimeter + "V_{Down} (ft/s)";
@@ -192,6 +268,8 @@ void FGOutput::DelimitedOutput(string fname)
       outstream << "Rho (slugs/ft^3)" + delimeter;
       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)";
     }
     if (SubSystems & ssMassProps) {
@@ -216,6 +294,8 @@ void FGOutput::DelimitedOutput(string fname)
       outstream << "Beta (deg)" + delimeter;
       outstream << "Latitude (deg)" + delimeter;
       outstream << "Longitude (deg)" + delimeter;
+      outstream << "ECEF X (ft)" + delimeter + "ECEF Y (ft)" + delimeter + "ECEF Z (ft)" + delimeter;
+      outstream << "EPA (deg)" + delimeter;
       outstream << "Distance AGL (ft)" + delimeter;
       outstream << "Runway Radius (ft)";
     }
@@ -269,13 +349,14 @@ void FGOutput::DelimitedOutput(string fname)
     outstream << delimeter;
     outstream << Auxiliary->Getqbar() << delimeter;
     outstream << setprecision(12) << Auxiliary->GetVt() << delimeter;
+    outstream << Propagate->GetInertialVelocityMagnitude() << delimeter;
     outstream << setprecision(12) << Propagate->GetUVW().Dump(delimeter) << delimeter;
     outstream << Auxiliary->GetAeroUVW().Dump(delimeter) << delimeter;
     outstream << Propagate->GetVel().Dump(delimeter);
   }
   if (SubSystems & ssForces) {
     outstream << delimeter;
-    outstream << Aerodynamics->GetvFs() << delimeter;
+    outstream << Aerodynamics->GetvFw() << delimeter;
     outstream << Aerodynamics->GetLoD() << delimeter;
     outstream << Aircraft->GetForces().Dump(delimeter);
   }
@@ -288,6 +369,8 @@ void FGOutput::DelimitedOutput(string fname)
     outstream << Atmosphere->GetDensity() << delimeter;
     outstream << Atmosphere->GetPressureSL() << delimeter;
     outstream << Atmosphere->GetPressure() << delimeter;
+    outstream << Atmosphere->GetTurbMagnitude() << delimeter;
+    outstream << Atmosphere->GetTurbDirection().Dump(delimeter) << delimeter;
     outstream << Atmosphere->GetWindNED().Dump(delimeter);
   }
   if (SubSystems & ssMassProps) {
@@ -304,6 +387,8 @@ void FGOutput::DelimitedOutput(string fname)
     outstream << Auxiliary->Getbeta(inDegrees) << delimeter;
     outstream << Propagate->GetLocation().GetLatitudeDeg() << delimeter;
     outstream << Propagate->GetLocation().GetLongitudeDeg() << delimeter;
+    outstream << ((FGColumnVector3)Propagate->GetLocation()).Dump(delimeter) << delimeter;
+    outstream << Inertial->GetEarthPositionAngleDeg() << delimeter;
     outstream << Propagate->GetDistanceAGL() << delimeter;
     outstream << Propagate->GetRunwayRadius();
   }
@@ -334,6 +419,220 @@ void FGOutput::DelimitedOutput(string fname)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGOutput::SocketDataFill(FGNetFDM* net)
+{
+    unsigned int i;
+
+    // Version
+    net->version = FG_NET_FDM_VERSION;
+
+    // Positions
+    net->longitude = Propagate->GetLocation().GetLongitude(); // geodetic (radians)
+    net->latitude  = Propagate->GetLocation().GetLatitude(); // geodetic (radians)
+    net->altitude  = Propagate->Geth()*0.3048; // altitude, above sea level (meters)
+    net->agl       = (float)(Propagate->GetDistanceAGL()*0.3048); // altitude, above ground level (meters)
+
+    net->phi       = (float)(Propagate->GetEuler(ePhi)); // roll (radians)
+    net->theta     = (float)(Propagate->GetEuler(eTht)); // pitch (radians)
+    net->psi       = (float)(Propagate->GetEuler(ePsi)); // yaw or true heading (radians)
+
+    net->alpha     = (float)(Auxiliary->Getalpha()); // angle of attack (radians)
+    net->beta      = (float)(Auxiliary->Getbeta()); // side slip angle (radians)
+
+    // Velocities
+    net->phidot     = (float)(Auxiliary->GetEulerRates(ePhi)); // roll rate (radians/sec)
+    net->thetadot   = (float)(Auxiliary->GetEulerRates(eTht)); // pitch rate (radians/sec)
+    net->psidot     = (float)(Auxiliary->GetEulerRates(ePsi)); // yaw rate (radians/sec)
+    net->vcas       = (float)(Auxiliary->GetVcalibratedFPS()); // VCAS, ft/sec
+    net->climb_rate = (float)(Propagate->Gethdot());           // altitude rate, ft/sec
+    net->v_north    = (float)(Propagate->GetVel(eNorth));      // north vel in NED frame, fps
+    net->v_east     = (float)(Propagate->GetVel(eEast));       // east vel in NED frame, fps
+    net->v_down     = (float)(Propagate->GetVel(eDown));       // down vel in NED frame, fps
+//---ADD METHOD TO CALCULATE THESE TERMS---
+    net->v_wind_body_north = (float)(Propagate->GetVel(eNorth)); // north vel in NED relative to airmass, fps
+    net->v_wind_body_east = (float)(Propagate->GetVel(eEast)); // east vel in NED relative to airmass, fps
+    net->v_wind_body_down = (float)(Propagate->GetVel(eDown)); // down vel in NED relative to airmass, fps
+
+    // Accelerations
+    net->A_X_pilot   = (float)(Auxiliary->GetPilotAccel(1));    // X body accel, ft/s/s
+    net->A_Y_pilot   = (float)(Auxiliary->GetPilotAccel(2));    // Y body accel, ft/s/s
+    net->A_Z_pilot   = (float)(Auxiliary->GetPilotAccel(3));    // Z body accel, ft/s/s
+
+    // Stall
+    net->stall_warning = 0.0;  // 0.0 - 1.0 indicating the amount of stall
+    net->slip_deg    = (float)(Auxiliary->Getbeta(inDegrees));  // slip ball deflection, deg
+
+    // Engine status
+    net->num_engines = Propulsion->GetNumEngines(); // Number of valid engines
+
+    for (i=0; i<net->num_engines; i++) {
+       if (Propulsion->GetEngine(i)->GetRunning())
+          net->eng_state[i] = 2;       // Engine state running
+       else if (Propulsion->GetEngine(i)->GetCranking())
+          net->eng_state[i] = 1;       // Engine state cranking
+       else
+          net->eng_state[i] = 0;       // Engine state off
+
+       switch (Propulsion->GetEngine(i)->GetType()) {
+       case (FGEngine::etRocket):
+       break;
+       case (FGEngine::etPiston):
+          net->rpm[i]       = (float)(((FGPiston *)Propulsion->GetEngine(i))->getRPM());
+          net->fuel_flow[i] = (float)(((FGPiston *)Propulsion->GetEngine(i))->getFuelFlow_gph());
+          net->fuel_px[i]   = 0; // Fuel pressure, psi  (N/A in current model)
+          net->egt[i]       = (float)(((FGPiston *)Propulsion->GetEngine(i))->GetEGT());
+          net->cht[i]       = (float)(((FGPiston *)Propulsion->GetEngine(i))->getCylinderHeadTemp_degF());
+          net->mp_osi[i]    = (float)(((FGPiston *)Propulsion->GetEngine(i))->getManifoldPressure_inHg());
+          net->oil_temp[i]  = (float)(((FGPiston *)Propulsion->GetEngine(i))->getOilTemp_degF());
+          net->oil_px[i]    = (float)(((FGPiston *)Propulsion->GetEngine(i))->getOilPressure_psi());
+          net->tit[i]       = 0; // Turbine Inlet Temperature  (N/A for piston)
+       break;
+       case (FGEngine::etTurbine):
+       break;
+       case (FGEngine::etTurboprop):
+       break;
+       case (FGEngine::etElectric):
+       break;
+       case (FGEngine::etUnknown):
+       break;
+       }
+    }
+
+
+    // Consumables
+    net->num_tanks = Propulsion->GetNumTanks();   // Max number of fuel tanks
+
+    for (i=0; i<net->num_tanks; i++) {
+       net->fuel_quantity[i] = (float)(((FGTank *)Propulsion->GetTank(i))->GetContents());
+    }
+
+
+    // Gear status
+    net->num_wheels  = GroundReactions->GetNumGearUnits();
+
+    for (i=0; i<net->num_wheels; i++) {
+       net->wow[i]              = GroundReactions->GetGearUnit(i)->GetWOW();
+       if (GroundReactions->GetGearUnit(i)->GetGearUnitDown())
+          net->gear_pos[i]      = 1;  //gear down, using FCS convention
+       else
+          net->gear_pos[i]      = 0;  //gear up, using FCS convention
+       net->gear_steer[i]       = (float)(GroundReactions->GetGearUnit(i)->GetSteerNorm());
+       net->gear_compression[i] = (float)(GroundReactions->GetGearUnit(i)->GetCompLen());
+    }
+
+
+    // Environment
+    net->cur_time    = (long int)1234567890;   // Friday, Feb 13, 2009, 23:31:30 UTC (not processed by FGFS anyway)
+    net->warp        = 0;                       // offset in seconds to unix time
+    net->visibility  = 25000.0;                 // visibility in meters (for env. effects)
+
+
+    // Control surface positions (normalized values)
+    net->elevator          = (float)(FCS->GetDePos(ofNorm));    // Norm Elevator Pos, --
+    net->elevator_trim_tab = (float)(FCS->GetPitchTrimCmd());   // Norm Elev Trim Tab Pos, --
+    net->left_flap         = (float)(FCS->GetDfPos(ofNorm));    // Norm Flap Pos, --
+    net->right_flap        = (float)(FCS->GetDfPos(ofNorm));    // Norm Flap Pos, --
+    net->left_aileron      = (float)(FCS->GetDaLPos(ofNorm));   // Norm L Aileron Pos, --
+    net->right_aileron     = (float)(FCS->GetDaRPos(ofNorm));   // Norm R Aileron Pos, --
+    net->rudder            = (float)(FCS->GetDrPos(ofNorm));    // Norm Rudder Pos, --
+    net->nose_wheel        = (float)(FCS->GetDrPos(ofNorm));    // *** FIX ***  Using Rudder Pos for NWS, --
+    net->speedbrake        = (float)(FCS->GetDsbPos(ofNorm));   // Norm Speedbrake Pos, --
+    net->spoilers          = (float)(FCS->GetDspPos(ofNorm));   // Norm Spoiler Pos, --
+
+
+    // Convert the net buffer to network format
+    if ( isLittleEndian ) {
+        net->version = htonl(net->version);
+
+        htond(net->longitude);
+        htond(net->latitude);
+        htond(net->altitude);
+        htonf(net->agl);
+        htonf(net->phi);
+        htonf(net->theta);
+        htonf(net->psi);
+        htonf(net->alpha);
+        htonf(net->beta);
+
+        htonf(net->phidot);
+        htonf(net->thetadot);
+        htonf(net->psidot);
+        htonf(net->vcas);
+        htonf(net->climb_rate);
+        htonf(net->v_north);
+        htonf(net->v_east);
+        htonf(net->v_down);
+        htonf(net->v_wind_body_north);
+        htonf(net->v_wind_body_east);
+        htonf(net->v_wind_body_down);
+
+        htonf(net->A_X_pilot);
+        htonf(net->A_Y_pilot);
+        htonf(net->A_Z_pilot);
+
+        htonf(net->stall_warning);
+        htonf(net->slip_deg);
+
+        for (i=0; i<net->num_engines; ++i ) {
+            net->eng_state[i] = htonl(net->eng_state[i]);
+            htonf(net->rpm[i]);
+            htonf(net->fuel_flow[i]);
+            htonf(net->fuel_px[i]);
+            htonf(net->egt[i]);
+            htonf(net->cht[i]);
+            htonf(net->mp_osi[i]);
+            htonf(net->tit[i]);
+            htonf(net->oil_temp[i]);
+            htonf(net->oil_px[i]);
+        }
+        net->num_engines = htonl(net->num_engines);
+
+        for (i=0; i<net->num_tanks; ++i ) {
+            htonf(net->fuel_quantity[i]);
+        }
+        net->num_tanks = htonl(net->num_tanks);
+
+        for (i=0; i<net->num_wheels; ++i ) {
+            net->wow[i] = htonl(net->wow[i]);
+            htonf(net->gear_pos[i]);
+            htonf(net->gear_steer[i]);
+            htonf(net->gear_compression[i]);
+        }
+        net->num_wheels = htonl(net->num_wheels);
+
+        net->cur_time = htonl( net->cur_time );
+        net->warp = htonl( net->warp );
+        htonf(net->visibility);
+
+        htonf(net->elevator);
+        htonf(net->elevator_trim_tab);
+        htonf(net->left_flap);
+        htonf(net->right_flap);
+        htonf(net->left_aileron);
+        htonf(net->right_aileron);
+        htonf(net->rudder);
+        htonf(net->nose_wheel);
+        htonf(net->speedbrake);
+        htonf(net->spoilers);
+    }
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGOutput::FlightGearSocketOutput(void)
+{
+  int length = sizeof(fgSockBuf);
+
+
+  if (flightGearSocket == NULL) return;
+  if (!flightGearSocket->GetConnectStatus()) return;
+
+  SocketDataFill(&fgSockBuf);
+  flightGearSocket->Send((char *)&fgSockBuf, length);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 void FGOutput::SocketOutput(void)
 {
   string asciiData, scratch;
@@ -398,6 +697,10 @@ void FGOutput::SocketOutput(void)
       socket->Append("Rho");
       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("NWind");
       socket->Append("EWind");
       socket->Append("DWind");
@@ -487,9 +790,9 @@ void FGOutput::SocketOutput(void)
     socket->Append(Propagate->GetVel(eDown));
   }
   if (SubSystems & ssForces) {
-    socket->Append(Aerodynamics->GetvFs()(eDrag));
-    socket->Append(Aerodynamics->GetvFs()(eSide));
-    socket->Append(Aerodynamics->GetvFs()(eLift));
+    socket->Append(Aerodynamics->GetvFw()(eDrag));
+    socket->Append(Aerodynamics->GetvFw()(eSide));
+    socket->Append(Aerodynamics->GetvFw()(eLift));
     socket->Append(Aerodynamics->GetLoD());
     socket->Append(Aircraft->GetForces(eX));
     socket->Append(Aircraft->GetForces(eY));
@@ -504,6 +807,8 @@ void FGOutput::SocketOutput(void)
     socket->Append(Atmosphere->GetDensity());
     socket->Append(Atmosphere->GetPressureSL());
     socket->Append(Atmosphere->GetPressure());
+    socket->Append(Atmosphere->GetTurbMagnitude());
+    socket->Append(Atmosphere->GetTurbDirection().Dump(","));
     socket->Append(Atmosphere->GetWindNED().Dump(","));
   }
   if (SubSystems & ssMassProps) {
@@ -572,7 +877,8 @@ void FGOutput::SocketStatusOutput(string out_str)
 bool FGOutput::Load(Element* element)
 {
   string type="", parameter="";
-  string name="", fname="";
+  string name="";
+  string protocol="tcp";
   int OutRate = 0;
   string property;
   unsigned int port;
@@ -584,18 +890,10 @@ bool FGOutput::Load(Element* element)
 # endif
 
   if (!DirectivesFile.empty()) { // A directives filename from the command line overrides
-    fname = DirectivesFile;      // one found in the config file.
-  } else {
-    fname = element->GetAttributeValue("file");
-  }
-
-  if (!fname.empty()) {
-    int len = fname.size();
-    if (fname.find(".xml") != string::npos) {
-      output_file_name = fname; // Use supplied name if last four letters are ".xml"
-    } else {
-      output_file_name = FDMExec->GetFullAircraftPath() + separator + fname + ".xml";
-    }
+    output_file_name = DirectivesFile;      // one found in the config file.
+    document = LoadXMLDocument(output_file_name);
+  } else if (!element->GetAttributeValue("file").empty()) {
+    output_file_name = element->GetAttributeValue("file");
     document = LoadXMLDocument(output_file_name);
   } else {
     document = element;
@@ -607,6 +905,14 @@ bool FGOutput::Load(Element* element)
   if (!document->GetAttributeValue("port").empty() && type == string("SOCKET")) {
     port = atoi(document->GetAttributeValue("port").c_str());
     socket = new FGfdmSocket(name, port);
+  } else if (!document->GetAttributeValue("port").empty() && type == string("FLIGHTGEAR")) {
+    port = atoi(document->GetAttributeValue("port").c_str());
+    if (!document->GetAttributeValue("protocol").empty())
+       protocol = document->GetAttributeValue("protocol");
+    if (protocol == "udp")
+       flightGearSocket = new FGfdmSocket(name, port, FGfdmSocket::ptUDP);  // create udp socket
+    else
+       flightGearSocket = new FGfdmSocket(name, port, FGfdmSocket::ptTCP);  // create tcp socket (default)
   } else {
     Filename = name;
   }
@@ -644,8 +950,16 @@ bool FGOutput::Load(Element* element)
     SubSystems += ssPropulsion;
   property_element = document->FindElement("property");
   while (property_element) {
-    string property = property_element->GetDataLine();
-    OutputProperties.push_back(PropertyManager->GetNode(property));
+    string property_str = property_element->GetDataLine();
+    FGPropertyManager* node = PropertyManager->GetNode(property_str);
+    if (!node) {
+      cerr << fgred << highint << endl << "  No property by the name "
+           << property_str << " has been defined. This property will " << endl
+           << "  not be logged. You should check your configuration file."
+           << reset << endl;
+    } else {
+      OutputProperties.push_back(node);
+    }
     property_element = document->FindNextElement("property");
   }
 
index 8d3f00b9ed44aec2ac682c547840aa095cd7b60e..335dcfeaf4bf79a4efa988d32d67dc95a94afa6a 100644 (file)
@@ -26,6 +26,7 @@
 HISTORY
 --------------------------------------------------------------------------------
 12/02/98   JSB   Created
+11/09/07   HDW   Added FlightGear Socket Interface
 
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 SENTRY
@@ -54,8 +55,10 @@ INCLUDES
 #  endif
 #endif
 
-#include <input_output/FGfdmSocket.h>
-#include <input_output/FGXMLFileRead.h>
+#include "input_output/FGfdmSocket.h"
+#include "input_output/FGXMLFileRead.h"
+#include "input_output/net_fdm.hxx"
+
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
@@ -77,23 +80,39 @@ CLASS DOCUMENTATION
     OUTPUT section definition
 
     The following specifies the way that JSBSim writes out data.
-
+<pre>
     NAME is the filename you want the output to go to
 
     TYPE can be:
-      CSV       Comma separated data. If a filename is supplied then the data
-                goes to that file. If COUT or cout is specified, the data goes
-                to stdout. If the filename is a null filename the data goes to
-                stdout, as well.
-      SOCKET    Will eventually send data to a socket output, where NAME
-                would then be the IP address of the machine the data should be
-                sent to. DON'T USE THIS YET!
-      TABULAR   Columnar data. NOT IMPLEMENTED YET!
-      TERMINAL  Output to terminal. NOT IMPLEMENTED YET!
-      NONE      Specifies to do nothing. THis setting makes it easy to turn on and
-                off the data output without having to mess with anything else.
-
-    The arguments that can be supplied, currently, are
+      CSV         Comma separated data. If a filename is supplied then the
+                  data goes to that file. If "COUT" or "cout" is specified, the
+                  data goes to stdout. If the filename is a null filename the
+                  data goes to stdout, as well.
+      SOCKET      Will eventually send data to a socket output, where NAME
+                  would then be the IP address of the machine the data should
+                  be sent to. DON'T USE THIS YET!
+      FLIGHTGEAR  A socket is created for sending binary data packets to
+                  an external instance of FlightGear for visuals.  Parameters
+                  defining the socket are given on the \<output> line.
+      TABULAR     Columnar data. NOT IMPLEMENTED YET!
+      TERMINAL    Output to terminal. NOT IMPLEMENTED YET!
+      NONE        Specifies to do nothing. This setting makes it easy to turn on and
+                  off the data output without having to mess with anything else.
+
+      Examples:
+</pre>
+@code
+       <output name="localhost" type="FLIGHTGEAR" port="5500" protocol="tcp" rate="10"></output>
+@endcode
+@code
+       <output name="B737_datalog.csv" type="CSV" rate="20">
+          <property> velocities/vc-kts </property>
+          <velocities> ON </velocities>
+       </output>
+@endcode
+<br>
+<pre>
+    The arguments that can be supplied, currently, are:
 
     RATE_IN_HZ  An integer rate in times-per-second that the data is output. This
                 value may not be *exactly* what you want, due to the dependence
@@ -101,20 +120,20 @@ CLASS DOCUMENTATION
 
     The following parameters tell which subsystems of data to output:
 
-    SIMULATION       ON|OFF
-    ATMOSPHERE       ON|OFF
-    MASSPROPS        ON|OFF
-    AEROSURFACES     ON|OFF
-    RATES            ON|OFF
-    VELOCITIES       ON|OFF
-    FORCES           ON|OFF
-    MOMENTS          ON|OFF
-    POSITION         ON|OFF
-    COEFFICIENTS     ON|OFF
-    GROUND_REACTIONS ON|OFF
-    FCS              ON|OFF
-    PROPULSION       ON|OFF
-
+    simulation       ON|OFF
+    atmosphere       ON|OFF
+    massprops        ON|OFF
+    aerosurfaces     ON|OFF
+    rates            ON|OFF
+    velocities       ON|OFF
+    forces           ON|OFF
+    moments          ON|OFF
+    position         ON|OFF
+    coefficients     ON|OFF
+    ground_reactions ON|OFF
+    fcs              ON|OFF
+    propulsion       ON|OFF
+</pre>
     NOTE that Time is always output with the data.
     @version $Id$
  */
@@ -129,11 +148,16 @@ public:
   FGOutput(FGFDMExec*);
   ~FGOutput();
 
+  bool InitModel(void);
   bool Run(void);
 
   void DelimitedOutput(string);
   void SocketOutput(void);
+  void FlightGearSocketOutput(void);
   void SocketStatusOutput(string);
+  void SocketDataFill(FGNetFDM* net);
+
+
   void SetType(string);
   void SetSubsystems(int tt) {SubSystems = tt;}
   inline void Enable(void) { enabled = true; }
@@ -161,13 +185,17 @@ public:
     /** Subsystem: Propulsion (= 4096)       */ ssPropulsion      = 4096
   } subsystems;
 
+
+  FGNetFDM fgSockBuf;
+
 private:
-  enum {otNone, otCSV, otTab, otSocket, otTerminal, otUnknown} Type;
+  enum {otNone, otCSV, otTab, otSocket, otTerminal, otFlightGear, otUnknown} Type;
   bool sFirstPass, dFirstPass, enabled;
   int SubSystems;
   string output_file_name, delimeter, Filename, DirectivesFile;
   ofstream datafile;
   FGfdmSocket* socket;
+  FGfdmSocket* flightGearSocket;
   vector <FGPropertyManager*> OutputProperties;
 
   void Debug(int from);
index a1211cd621baf494a2c3ccfd327ca9beed0c240e..2f2abc6475ccf1ab5c72db46eecddb8a6f4e4f5e 100644 (file)
@@ -95,8 +95,8 @@ CLASS IMPLEMENTATION
 
 FGPropagate::FGPropagate(FGFDMExec* fdmex) : FGModel(fdmex)
 {
+  Debug(0);
   Name = "FGPropagate";
-//  vQtrndot.zero();
 
   last2_vPQRdot.InitMatrix();
   last_vPQRdot.InitMatrix();
@@ -110,6 +110,13 @@ FGPropagate::FGPropagate(FGFDMExec* fdmex) : FGModel(fdmex)
   last_vLocationDot.InitMatrix();
   vLocationDot.InitMatrix();
 
+  vOmegaLocal.InitMatrix();
+
+  integrator_rotational_rate = eAdamsBashforth2;
+  integrator_translational_rate = eAdamsBashforth2;
+  integrator_rotational_position = eTrapezoidal;
+  integrator_translational_position = eTrapezoidal;
+
   bind();
   Debug(0);
 }
@@ -118,7 +125,6 @@ FGPropagate::FGPropagate(FGFDMExec* fdmex) : FGModel(fdmex)
 
 FGPropagate::~FGPropagate(void)
 {
-  unbind();
   Debug(1);
 }
 
@@ -126,12 +132,33 @@ FGPropagate::~FGPropagate(void)
 
 bool FGPropagate::InitModel(void)
 {
-  FGModel::InitModel();
+  if (!FGModel::InitModel()) return false;
 
-  SeaLevelRadius = Inertial->RefRadius();          // For initialization ONLY
+  SeaLevelRadius = Inertial->GetRefRadius();          // For initialization ONLY
   RunwayRadius   = SeaLevelRadius;
 
-  VState.vLocation.SetRadius( SeaLevelRadius + 4.0 );
+  VState.vLocation.SetRadius( SeaLevelRadius + 4.0 ); // Todo Add terrain elevation?
+  VState.vLocation.SetEllipse(Inertial->GetSemimajor(), Inertial->GetSemiminor());
+  vOmega = FGColumnVector3( 0.0, 0.0, Inertial->omega() ); // Earth rotation vector
+
+  last2_vPQRdot.InitMatrix();
+  last_vPQRdot.InitMatrix();
+  vPQRdot.InitMatrix();
+  
+  last2_vUVWdot.InitMatrix();
+  last_vUVWdot.InitMatrix();
+  vUVWdot.InitMatrix();
+  
+  last2_vLocationDot.InitMatrix();
+  last_vLocationDot.InitMatrix();
+  vLocationDot.InitMatrix();
+
+  vOmegaLocal.InitMatrix();
+
+  integrator_rotational_rate = eAdamsBashforth2;
+  integrator_translational_rate = eAdamsBashforth2;
+  integrator_rotational_position = eTrapezoidal;
+  integrator_translational_position = eTrapezoidal;
 
   return true;
 }
@@ -144,10 +171,13 @@ void FGPropagate::SetInitialState(const FGInitialCondition *FGIC)
   RunwayRadius = SeaLevelRadius;
 
   // Set the position lat/lon/radius
-  VState.vLocation = FGLocation( FGIC->GetLongitudeRadIC(),
+  VState.vLocation.SetPosition( FGIC->GetLongitudeRadIC(),
                           FGIC->GetLatitudeRadIC(),
                           FGIC->GetAltitudeFtIC() + FGIC->GetSeaLevelRadiusFtIC() );
 
+  VehicleRadius = GetRadius();
+  radInv = 1.0/VehicleRadius;
+
   // Set the Orientation from the euler angles
   VState.vQtrn = FGQuaternion( FGIC->GetPhiRadIC(),
                         FGIC->GetThetaRadIC(),
@@ -163,8 +193,8 @@ void FGPropagate::SetInitialState(const FGInitialCondition *FGIC)
                           FGIC->GetQRadpsIC(),
                           FGIC->GetRRadpsIC() );
 
-  // Compute some derived values.
-  vVel = VState.vQtrn.GetTInv()*VState.vUVW;
+  // Compute the local frame ECEF velocity
+  vVel = GetTb2l()*VState.vUVW;
 
   // Finally, make sure that the quaternion stays normalized.
   VState.vQtrn.Normalize();
@@ -182,11 +212,15 @@ Notes:   [JB] Run in standalone mode, SeaLevelRadius will be reference radius.
 At the top of this Run() function, see several "shortcuts" (or, aliases) being
 set up for use later, rather than using the longer class->function() notation.
 
-Here, propagation of state is done using a simple explicit Euler scheme (see the
-bottom of the function). This propagation is done using the current state values
+This propagation is done using the current state values
 and current derivatives. Based on these values we compute an approximation to the
 state values for (now + dt).
 
+In the code below, variables named beginning with a small "v" refer to a 
+a column vector, variables named beginning with a "T" refer to a transformation
+matrix. ECEF refers to Earth Centered Earth Fixed. ECI refers to Earth Centered
+Inertial.
+
 */
 
 bool FGPropagate::Run(void)
@@ -196,93 +230,101 @@ bool FGPropagate::Run(void)
 
   RecomputeRunwayRadius();
 
-  double dt = State->Getdt()*rate;  // The 'stepsize'
-  const FGColumnVector3 omega( 0.0, 0.0, Inertial->omega() ); // earth rotation
-  const FGColumnVector3& vForces = Aircraft->GetForces();     // current forces
-  const FGColumnVector3& vMoments = Aircraft->GetMoments();   // current moments
-
-  double mass = MassBalance->GetMass();             // mass
-  const FGMatrix33& J = MassBalance->GetJ();        // inertia matrix
-  const FGMatrix33& Jinv = MassBalance->GetJinv();  // inertia matrix inverse
-  double r = GetRadius();                           // radius
-  if (r == 0.0) {cerr << "radius = 0 !" << endl; r = 1e-16;} // radius check
-  double rInv = 1.0/r;
-  FGColumnVector3 gAccel( 0.0, 0.0, Inertial->GetGAccel(r) );
-
-  // The rotation matrices:
-  const FGMatrix33& Tl2b = GetTl2b();  // local to body frame
-  const FGMatrix33& Tb2l = GetTb2l();  // body to local frame
-  const FGMatrix33& Tec2l = VState.vLocation.GetTec2l();  // earth centered to local frame
-  const FGMatrix33& Tl2ec = VState.vLocation.GetTl2ec();  // local to earth centered frame
-
-  // Inertial angular velocity measured in the body frame.
-  const FGColumnVector3 pqri = VState.vPQR + Tl2b*(Tec2l*omega);
-
-  // Compute vehicle velocity wrt EC frame, expressed in Local horizontal frame.
-  vVel = Tb2l * VState.vUVW;
-
-  // First compute the time derivatives of the vehicle state values:
+  // Calculate current aircraft radius from center of planet
 
-  // Compute body frame rotational accelerations based on the current body moments
-  vPQRdot = Jinv*(vMoments - pqri*(J*pqri));
+  VehicleRadius = GetRadius();
+  radInv = 1.0/VehicleRadius;
 
-  // Compute body frame accelerations based on the current body forces
-  vUVWdot = VState.vUVW*VState.vPQR + vForces/mass;
+  // These local copies of the transformation matrices are for use this
+  // pass through Run() only.
 
-  // Coriolis acceleration.
-  FGColumnVector3 ecVel = Tl2ec*vVel;
-  FGColumnVector3 ace = 2.0*omega*ecVel;
-  vUVWdot -= Tl2b*(Tec2l*ace);
+  Tl2b = GetTl2b();           // local to body frame transform
+  Tb2l = Tl2b.Transposed();   // body to local frame transform
+  Tl2ec = GetTl2ec();         // local to ECEF transform
+  Tec2l = Tl2ec.Transposed(); // ECEF to local frame transform
+  Tec2b = Tl2b * Tec2l;       // ECEF to body frame transform
+  Tb2ec = Tec2b.Transposed(); // body to ECEF frame tranform
+  Ti2ec = GetTi2ec();         // ECI to ECEF transform
+  Tec2i = Ti2ec.Transposed(); // ECEF to ECI frame transform
+  Ti2b  = Tec2b*Ti2ec;        // ECI to body frame transform
+  Tb2i  = Ti2b.Transposed();  // body to ECI frame transform
 
-  if (!GroundReactions->GetWOW()) {
-    // Centrifugal acceleration.
-    FGColumnVector3 aeec = omega*(omega*VState.vLocation);
-    vUVWdot -= Tl2b*(Tec2l*aeec);
-  }
-
-  // Gravitation accel
-  vUVWdot += Tl2b*gAccel;
-
-  // Compute vehicle velocity wrt EC frame, expressed in EC frame
-  vLocationDot = Tl2ec * vVel;
+  // Compute vehicle velocity wrt ECEF frame, expressed in Local horizontal frame.
+  vVel = Tb2l * VState.vUVW;
 
-  FGColumnVector3 omegaLocal( rInv*vVel(eEast),
-                              -rInv*vVel(eNorth),
-                              -rInv*vVel(eEast)*VState.vLocation.GetTanLatitude() );
+  // Inertial angular velocity measured in the body frame.
+  vPQRi = VState.vPQR + Tec2b*vOmega;
 
-  // Compute quaternion orientation derivative on current body rates
-  vQtrndot = VState.vQtrn.GetQDot( VState.vPQR - Tl2b*omegaLocal );
+  // Calculate state derivatives
+  CalculatePQRdot();      // Angular rate derivative
+  CalculateUVWdot();      // Translational rate derivative
+  CalculateQuatdot();     // Angular orientation derivative
+  CalculateLocationdot(); // Translational position derivative
 
   // Integrate to propagate the state
 
-  // Propagate rotational velocity
+  double dt = State->Getdt()*rate;  // The 'stepsize'
 
-  // VState.vPQR += dt*(1.5*vPQRdot - 0.5*last_vPQRdot); // Adams-Bashforth
-  VState.vPQR += (1/12.0)*dt*(23.0*vPQRdot - 16.0*last_vPQRdot + 5.0*last2_vPQRdot); // Adams-Bashforth 3
-  // VState.vPQR += dt*vPQRdot;                          // Rectangular Euler
-  // VState.vPQR += 0.5*dt*(vPQRdot + last_vPQRdot);     // Trapezoidal
+  // Propagate rotational velocity
 
+  switch(integrator_rotational_rate) {
+  case eRectEuler:       VState.vPQR += dt*vPQRdot;
+    break;
+  case eTrapezoidal:     VState.vPQR += 0.5*dt*(vPQRdot + last_vPQRdot);
+    break;
+  case eAdamsBashforth2: VState.vPQR += dt*(1.5*vPQRdot - 0.5*last_vPQRdot);
+    break;
+  case eAdamsBashforth3: VState.vPQR += (1/12.0)*dt*(23.0*vPQRdot - 16.0*last_vPQRdot + 5.0*last2_vPQRdot);
+    break;
+  case eNone: // do nothing, freeze angular rate
+    break;
+  }
+  
   // Propagate translational velocity
 
-  // VState.vUVW += dt*(1.5*vUVWdot - 0.5*last_vUVWdot); // Adams Bashforth
-  VState.vUVW += (1/12.0)*dt*(23.0*vUVWdot - 16.0*last_vUVWdot + 5.0*last2_vUVWdot); // Adams-Bashforth 3
-  // VState.vUVW += dt*vUVWdot;                         // Rectangular Euler
-  // VState.vUVW += 0.5*dt*(vUVWdot + last_vUVWdot);    // Trapezoidal
+  switch(integrator_translational_rate) {
+  case eRectEuler:       VState.vUVW += dt*vUVWdot;
+    break;
+  case eTrapezoidal:     VState.vUVW += 0.5*dt*(vUVWdot + last_vUVWdot);
+    break;
+  case eAdamsBashforth2: VState.vUVW += dt*(1.5*vUVWdot - 0.5*last_vUVWdot);
+    break;
+  case eAdamsBashforth3: VState.vUVW += (1/12.0)*dt*(23.0*vUVWdot - 16.0*last_vUVWdot + 5.0*last2_vUVWdot);
+    break;
+  case eNone: // do nothing, freeze translational rate
+    break;
+  }
 
   // Propagate angular position
 
-  // VState.vQtrn += dt*(1.5*vQtrndot - 0.5*last_vQtrndot); // Adams Bashforth
-  VState.vQtrn += (1/12.0)*dt*(23.0*vQtrndot - 16.0*last_vQtrndot + 5.0*last2_vQtrndot); // Adams-Bashforth 3
-  // VState.vQtrn += dt*vQtrndot;                           // Rectangular Euler
-  // VState.vQtrn += 0.5*dt*(vQtrndot + last_vQtrndot);     // Trapezoidal
+  switch(integrator_rotational_position) {
+  case eRectEuler:       VState.vQtrn += dt*vQtrndot;
+    break;
+  case eTrapezoidal:     VState.vQtrn += 0.5*dt*(vQtrndot + last_vQtrndot);
+    break;
+  case eAdamsBashforth2: VState.vQtrn += dt*(1.5*vQtrndot - 0.5*last_vQtrndot);
+    break;
+  case eAdamsBashforth3: VState.vQtrn += (1/12.0)*dt*(23.0*vQtrndot - 16.0*last_vQtrndot + 5.0*last2_vQtrndot);
+    break;
+  case eNone: // do nothing, freeze angular position
+    break;
+  }
 
   // Propagate translational position
 
-  // VState.vLocation += dt*(1.5*vLocationDot - 0.5*last_vLocationDot); // Adams Bashforth
-  VState.vLocation += (1/12.0)*dt*(23.0*vLocationDot - 16.0*last_vLocationDot + 5.0*last2_vLocationDot); // Adams-Bashforth 3
-  // VState.vLocation += dt*vLocationDot;                               // Rectangular Euler
-  // VState.vLocation += 0.5*dt*(vLocationDot + last_vLocationDot);     // Trapezoidal
-
+  switch(integrator_translational_position) {
+  case eRectEuler:       VState.vLocation += dt*vLocationDot;
+    break;
+  case eTrapezoidal:     VState.vLocation += 0.5*dt*(vLocationDot + last_vLocationDot);
+    break;
+  case eAdamsBashforth2: VState.vLocation += dt*(1.5*vLocationDot - 0.5*last_vLocationDot);
+    break;
+  case eAdamsBashforth3: VState.vLocation += (1/12.0)*dt*(23.0*vLocationDot - 16.0*last_vLocationDot + 5.0*last2_vLocationDot);
+    break;
+  case eNone: // do nothing, freeze translational position
+    break;
+  }
+  
   // Set past values
   
   last2_vPQRdot = last_vPQRdot;
@@ -300,6 +342,97 @@ bool FGPropagate::Run(void)
   return false;
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+// Compute body frame rotational accelerations based on the current body moments
+//
+// vPQRdot is the derivative of the absolute angular velocity of the vehicle 
+// (body rate with respect to the inertial frame), expressed in the body frame,
+// where the derivative is taken in the body frame.
+// J is the inertia matrix
+// Jinv is the inverse inertia matrix
+// vMoments is the moment vector in the body frame
+// vPQRi is the total inertial angular velocity of the vehicle
+// expressed in the body frame.
+// Reference: See Stevens and Lewis, "Aircraft Control and Simulation", 
+//            Second edition (2004), eqn 1.5-16e (page 50)
+
+void FGPropagate::CalculatePQRdot(void)
+{
+  const FGColumnVector3& vMoments = Aircraft->GetMoments(); // current moments
+  const FGMatrix33& J = MassBalance->GetJ();                // inertia matrix
+  const FGMatrix33& Jinv = MassBalance->GetJinv();          // inertia matrix inverse
+
+  // Compute body frame rotational accelerations based on the current body
+  // moments and the total inertial angular velocity expressed in the body
+  // frame.
+
+  vPQRdot = Jinv*(vMoments - vPQRi*(J*vPQRi));
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+// Compute the quaternion orientation derivative
+//
+// vQtrndot is the quaternion derivative.
+// Reference: See Stevens and Lewis, "Aircraft Control and Simulation", 
+//            Second edition (2004), eqn 1.5-16b (page 50)
+
+void FGPropagate::CalculateQuatdot(void)
+{
+  vOmegaLocal.InitMatrix( radInv*vVel(eEast),
+                         -radInv*vVel(eNorth),
+                         -radInv*vVel(eEast)*VState.vLocation.GetTanLatitude() );
+
+  // Compute quaternion orientation derivative on current body rates
+  vQtrndot = VState.vQtrn.GetQDot( VState.vPQR - Tl2b*vOmegaLocal);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+// This set of calculations results in the body frame accelerations being
+// computed.
+// Reference: See Stevens and Lewis, "Aircraft Control and Simulation", 
+//            Second edition (2004), eqn 1.5-16d (page 50)
+
+void FGPropagate::CalculateUVWdot(void)
+{
+  double mass = MassBalance->GetMass();                      // mass
+  const FGColumnVector3& vForces = Aircraft->GetForces();    // current forces
+
+  const FGColumnVector3 vGravAccel( 0.0, 0.0, Inertial->GetGAccel(VehicleRadius) );
+
+  // Begin to compute body frame accelerations based on the current body forces
+  vUVWdot = vForces/mass - VState.vPQR * VState.vUVW;
+
+  // Include Coriolis acceleration.
+  vUVWdot -= 2.0 * (Ti2b *vOmega) * VState.vUVW;
+
+  // Include Centrifugal acceleration.
+  if (!GroundReactions->GetWOW()) {
+    vUVWdot -= Ti2b*(vOmega*(vOmega*(Tec2i*VState.vLocation)));
+  }
+
+  // Include Gravitation accel
+  FGColumnVector3 gravAccel = Tl2b*vGravAccel;
+  vUVWdot += gravAccel;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGPropagate::CalculateLocationdot(void)
+{
+  // Transform the vehicle velocity relative to the ECEF frame, expressed
+  // in the body frame, to be expressed in the ECEF frame.
+  vLocationDot = Tb2ec * VState.vUVW;
+
+  // Now, transform the velocity vector of the body relative to the origin (Earth
+  // center) to be expressed in the inertial frame, and add the vehicle velocity
+  // contribution due to the rotation of the planet. The above velocity is only
+  // relative to the rotating ECEF frame.
+  // Reference: See Stevens and Lewis, "Aircraft Control and Simulation", 
+  //            Second edition (2004), eqn 1.5-16c (page 50)
+
+  vInertialVelocity = Tec2i * vLocationDot + (vOmega * (Tec2i * VState.vLocation));
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
 void FGPropagate::RecomputeRunwayRadius(void)
@@ -315,6 +448,34 @@ void FGPropagate::RecomputeRunwayRadius(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGPropagate::SetTerrainElevationASL(double tt)
+{
+  FDMExec->GetGroundCallback()->SetTerrainGeoCentRadius(tt+SeaLevelRadius);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+double FGPropagate::GetTerrainElevationASL(void) const
+{
+  return FDMExec->GetGroundCallback()->GetTerrainGeoCentRadius()-SeaLevelRadius;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+const FGMatrix33& FGPropagate::GetTi2ec(void)
+{
+  return VState.vLocation.GetTi2ec(Inertial->GetEarthPositionAngle());
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+const FGMatrix33& FGPropagate::GetTec2i(void)
+{
+  return VState.vLocation.GetTec2i(Inertial->GetEarthPositionAngle());
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 void FGPropagate::Seth(double tt)
 {
   VState.vLocation.SetRadius( tt + SeaLevelRadius );
@@ -346,6 +507,7 @@ void FGPropagate::SetDistanceAGL(double tt)
 void FGPropagate::bind(void)
 {
   typedef double (FGPropagate::*PMF)(int) const;
+//  typedef double (FGPropagate::*dPMF)() const;
   PropertyManager->Tie("velocities/h-dot-fps", this, &FGPropagate::Gethdot);
 
   PropertyManager->Tie("velocities/v-north-fps", this, eNorth, (PMF)&FGPropagate::GetVel);
@@ -360,19 +522,30 @@ void FGPropagate::bind(void)
   PropertyManager->Tie("velocities/q-rad_sec", this, eQ, (PMF)&FGPropagate::GetPQR);
   PropertyManager->Tie("velocities/r-rad_sec", this, eR, (PMF)&FGPropagate::GetPQR);
 
-  PropertyManager->Tie("accelerations/pdot-rad_sec", this, eP, (PMF)&FGPropagate::GetPQRdot);
-  PropertyManager->Tie("accelerations/qdot-rad_sec", this, eQ, (PMF)&FGPropagate::GetPQRdot);
-  PropertyManager->Tie("accelerations/rdot-rad_sec", this, eR, (PMF)&FGPropagate::GetPQRdot);
+  PropertyManager->Tie("velocities/eci-velocity-mag-fps", this, &FGPropagate::GetInertialVelocityMagnitude);
+
+  PropertyManager->Tie("accelerations/pdot-rad_sec2", this, eP, (PMF)&FGPropagate::GetPQRdot);
+  PropertyManager->Tie("accelerations/qdot-rad_sec2", this, eQ, (PMF)&FGPropagate::GetPQRdot);
+  PropertyManager->Tie("accelerations/rdot-rad_sec2", this, eR, (PMF)&FGPropagate::GetPQRdot);
 
-  PropertyManager->Tie("accelerations/udot-fps", this, eU, (PMF)&FGPropagate::GetUVWdot);
-  PropertyManager->Tie("accelerations/vdot-fps", this, eV, (PMF)&FGPropagate::GetUVWdot);
-  PropertyManager->Tie("accelerations/wdot-fps", this, eW, (PMF)&FGPropagate::GetUVWdot);
+  PropertyManager->Tie("accelerations/udot-ft_sec2", this, eU, (PMF)&FGPropagate::GetUVWdot);
+  PropertyManager->Tie("accelerations/vdot-ft_sec2", this, eV, (PMF)&FGPropagate::GetUVWdot);
+  PropertyManager->Tie("accelerations/wdot-ft_sec2", this, eW, (PMF)&FGPropagate::GetUVWdot);
 
   PropertyManager->Tie("position/h-sl-ft", this, &FGPropagate::Geth, &FGPropagate::Seth, true);
+  PropertyManager->Tie("position/h-sl-meters", this, &FGPropagate::Gethmeters, &FGPropagate::Sethmeters, true);
   PropertyManager->Tie("position/lat-gc-rad", this, &FGPropagate::GetLatitude, &FGPropagate::SetLatitude);
   PropertyManager->Tie("position/long-gc-rad", this, &FGPropagate::GetLongitude, &FGPropagate::SetLongitude);
+  PropertyManager->Tie("position/lat-gc-deg", this, &FGPropagate::GetLatitudeDeg, &FGPropagate::SetLatitudeDeg);
+  PropertyManager->Tie("position/long-gc-deg", this, &FGPropagate::GetLongitudeDeg, &FGPropagate::SetLongitudeDeg);
+  PropertyManager->Tie("position/lat-geod-rad", this, &FGPropagate::GetGeodLatitudeRad);
+  PropertyManager->Tie("position/lat-geod-deg", this, &FGPropagate::GetGeodLatitudeDeg);
+  PropertyManager->Tie("position/geod-alt-ft", this, &FGPropagate::GetGeodeticAltitude);
   PropertyManager->Tie("position/h-agl-ft", this,  &FGPropagate::GetDistanceAGL, &FGPropagate::SetDistanceAGL);
   PropertyManager->Tie("position/radius-to-vehicle-ft", this, &FGPropagate::GetRadius);
+  PropertyManager->Tie("position/terrain-elevation-asl-ft", this,
+                          &FGPropagate::GetTerrainElevationASL,
+                          &FGPropagate::SetTerrainElevationASL, false);
 
   PropertyManager->Tie("metrics/runway-radius", this, &FGPropagate::GetRunwayRadius);
 
@@ -383,40 +556,11 @@ void FGPropagate::bind(void)
   PropertyManager->Tie("attitude/roll-rad", this, (int)ePhi, (PMF)&FGPropagate::GetEuler);
   PropertyManager->Tie("attitude/pitch-rad", this, (int)eTht, (PMF)&FGPropagate::GetEuler);
   PropertyManager->Tie("attitude/heading-true-rad", this, (int)ePsi, (PMF)&FGPropagate::GetEuler);
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGPropagate::unbind(void)
-{
-  PropertyManager->Untie("velocities/v-north-fps");
-  PropertyManager->Untie("velocities/v-east-fps");
-  PropertyManager->Untie("velocities/v-down-fps");
-  PropertyManager->Untie("velocities/h-dot-fps");
-  PropertyManager->Untie("velocities/u-fps");
-  PropertyManager->Untie("velocities/v-fps");
-  PropertyManager->Untie("velocities/w-fps");
-  PropertyManager->Untie("velocities/p-rad_sec");
-  PropertyManager->Untie("velocities/q-rad_sec");
-  PropertyManager->Untie("velocities/r-rad_sec");
-  PropertyManager->Untie("accelerations/udot-fps");
-  PropertyManager->Untie("accelerations/vdot-fps");
-  PropertyManager->Untie("accelerations/wdot-fps");
-  PropertyManager->Untie("accelerations/pdot-rad_sec");
-  PropertyManager->Untie("accelerations/qdot-rad_sec");
-  PropertyManager->Untie("accelerations/rdot-rad_sec");
-  PropertyManager->Untie("position/h-sl-ft");
-  PropertyManager->Untie("position/lat-gc-rad");
-  PropertyManager->Untie("position/long-gc-rad");
-  PropertyManager->Untie("position/h-agl-ft");
-  PropertyManager->Untie("position/radius-to-vehicle-ft");
-  PropertyManager->Untie("metrics/runway-radius");
-  PropertyManager->Untie("attitude/phi-rad");
-  PropertyManager->Untie("attitude/theta-rad");
-  PropertyManager->Untie("attitude/psi-rad");
-  PropertyManager->Untie("attitude/roll-rad");
-  PropertyManager->Untie("attitude/pitch-rad");
-  PropertyManager->Untie("attitude/heading-true-rad");
+  
+  PropertyManager->Tie("simulation/integrator/rate/rotational", &integrator_rotational_rate);
+  PropertyManager->Tie("simulation/integrator/rate/translational", &integrator_translational_rate);
+  PropertyManager->Tie("simulation/integrator/position/rotational", &integrator_rotational_position);
+  PropertyManager->Tie("simulation/integrator/position/translational", &integrator_translational_position);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index a554a9cb2847b28db7eaaafd54c0df2682fc77e4..7446c38e234d2315240a25e6a7c189dbd08fa4c4 100644 (file)
@@ -43,6 +43,7 @@ INCLUDES
 #include <initialization/FGInitialCondition.h>
 #include <math/FGLocation.h>
 #include <math/FGQuaternion.h>
+#include <math/FGMatrix33.h>
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
@@ -60,7 +61,32 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Models the EOM and integration/propagation of state
+/** Models the EOM and integration/propagation of state.
+    The Equations of Motion (EOM) for JSBSim are integrated to propagate the
+    state of the vehicle given the forces and moments that act on it. The
+    integration accounts for a rotating Earth.
+    Integration of rotational and translation position and rate can be 
+    customized as needed or frozen by the selection of no integrator. The
+    selection of which integrator to use is done through the setting of 
+    the associated property. There are four properties which can be set:
+    
+    @code
+    simulation/integrator/rate/rotational
+    simulation/integrator/rate/translational
+    simulation/integrator/position/rotational
+    simulation/integrator/position/translational
+    @endcode
+    
+    Each of the integrators listed above can be set to one of the following values:
+
+    @code
+    0: No integrator (Freeze)
+    1: Rectangular Euler
+    2: Trapezoidal
+    3: Adams Bashforth 2
+    4: Adams Bashforth 3
+    @endcode
+
     @author Jon S. Berndt, Mathias Froehlich
     @version $Id$
   */
@@ -69,83 +95,375 @@ CLASS DOCUMENTATION
 CLASS DECLARATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-// state vector
-
-struct VehicleState {
-  FGLocation vLocation;
-  FGColumnVector3 vUVW;
-  FGColumnVector3 vPQR;
-  FGQuaternion vQtrn;
-};
-
 class FGPropagate : public FGModel {
 public:
-  /** Constructor
+  /** Constructor.
+      The constructor initializes several variables, and sets the initial set
+      of integrators to use as follows:
+      - integrator, rotational rate = Adams Bashforth 2
+      - integrator, translational rate = Adams Bashforth 2
+      - integrator, rotational position = Trapezoidal
+      - integrator, translational position = Trapezoidal
       @param Executive a pointer to the parent executive object */
   FGPropagate(FGFDMExec* Executive);
 
   /// Destructor
   ~FGPropagate();
+  
+  /// These define the indices use to select the various integrators.
+  enum eIntegrateType {eNone = 0, eRectEuler, eTrapezoidal, eAdamsBashforth2, eAdamsBashforth3};
+
+/** The current vehicle state vector structure contains the translational and
+    angular position, and the translational and angular velocity. */
+struct VehicleState {
+  /** Represents the current location of the vehicle in Earth centered Earth
+      fixed (ECEF) frame.
+      units ft */
+  FGLocation vLocation;
+  /** The velocity vector of the vehicle with respect to the ECEF frame,
+      expressed in the body system.
+      units ft/sec */
+  FGColumnVector3 vUVW;
+  /** The angular velocity vector for the vehicle relative to the ECEF frame,
+      expressed in the body frame.
+      units rad/sec */
+  FGColumnVector3 vPQR;
+  /** The current orientation of the vehicle, that is, the orientation of the
+      body frame relative to the local, vehilce-carried, NED frame. */
+  FGQuaternion vQtrn;
+};
 
+  /** Initializes the FGPropagate class after instantiation and prior to first execution.
+      The base class FGModel::InitModel is called first, initializing pointers to the 
+      other FGModel objects (and others).  */
   bool InitModel(void);
 
-  /** Runs the Propagate model; called by the Executive
+  /** Runs the Propagate model; called by the Executive.
       @return false if no error */
   bool Run(void);
 
+  /** Retrieves the velocity vector.
+      The vector returned is represented by an FGColumnVector reference. The vector
+      for the velocity in Local frame is organized (Vnorth, Veast, Vdown). The vector
+      is 1-based, so that the first element can be retrieved using the "()" operator.
+      In other words, vVel(1) is Vnorth. Various convenience enumerators are defined
+      in FGJSBBase. The relevant enumerators for the vector returned by this call are,
+      eNorth=1, eEast=2, eDown=3.
+      units ft/sec
+      @return The vehicle velocity vector with respect to the Earth centered frame,
+              expressed in Local horizontal frame.
+  */
   const FGColumnVector3& GetVel(void) const { return vVel; }
+  
+  /** Retrieves the body frame vehicle velocity vector.
+      The vector returned is represented by an FGColumnVector reference. The vector
+      for the velocity in Body frame is organized (Vx, Vy, Vz). The vector
+      is 1-based, so that the first element can be retrieved using the "()" operator.
+      In other words, vUVW(1) is Vx. Various convenience enumerators are defined
+      in FGJSBBase. The relevant enumerators for the vector returned by this call are,
+      eX=1, eY=2, eZ=3.
+      units ft/sec
+      @return The body frame vehicle velocity vector in ft/sec.
+  */
   const FGColumnVector3& GetUVW(void) const { return VState.vUVW; }
+  
+  /** Retrieves the body axis acceleration.
+      Retrieves the computed body axis accelerations based on the
+      applied forces and accounting for a rotating body frame.
+      The vector returned is represented by an FGColumnVector reference. The vector
+      for the acceleration in Body frame is organized (Ax, Ay, Az). The vector
+      is 1-based, so that the first element can be retrieved using the "()" operator.
+      In other words, vUVWdot(1) is Ax. Various convenience enumerators are defined
+      in FGJSBBase. The relevant enumerators for the vector returned by this call are,
+      eX=1, eY=2, eZ=3.
+      units ft/sec^2
+      @return Body axis translational acceleration in ft/sec^2.
+  */
   const FGColumnVector3& GetUVWdot(void) const { return vUVWdot; }
+  
+  /** Retrieves the body angular rates vector.
+      Retrieves the body angular rates (p, q, r), which are calculated by integration
+      of the angular acceleration.
+      The vector returned is represented by an FGColumnVector reference. The vector
+      for the angular velocity in Body frame is organized (P, Q, R). The vector
+      is 1-based, so that the first element can be retrieved using the "()" operator.
+      In other words, vPQR(1) is P. Various convenience enumerators are defined
+      in FGJSBBase. The relevant enumerators for the vector returned by this call are,
+      eP=1, eQ=2, eR=3.
+      units rad/sec
+      @return The body frame angular rates in rad/sec.
+  */
   const FGColumnVector3& GetPQR(void) const {return VState.vPQR;}
+  
+  /** Retrieves the body axis angular acceleration vector.
+      Retrieves the body axis angular acceleration vector in rad/sec^2. The
+      angular acceleration vector is determined from the applied forces and
+      accounts for a rotating frame.
+      The vector returned is represented by an FGColumnVector reference. The vector
+      for the angular acceleration in Body frame is organized (Pdot, Qdot, Rdot). The vector
+      is 1-based, so that the first element can be retrieved using the "()" operator.
+      In other words, vPQRdot(1) is Pdot. Various convenience enumerators are defined
+      in FGJSBBase. The relevant enumerators for the vector returned by this call are,
+      eP=1, eQ=2, eR=3.
+      units rad/sec^2
+      @return The angular acceleration vector.
+  */
   const FGColumnVector3& GetPQRdot(void) const {return vPQRdot;}
+  
+  /** Retrieves the Euler angles that define the vehicle orientation.
+      Extracts the Euler angles from the quaternion that stores the orientation
+      in the Local frame. The order of rotation used is Yaw-Pitch-Roll. The
+      vector returned is represented by an FGColumnVector reference. The vector
+      for the Euler angles is organized (Phi, Theta, Psi). The vector
+      is 1-based, so that the first element can be retrieved using the "()" operator.
+      In other words, the returned vector item with subscript (1) is Phi.
+      Various convenience enumerators are defined in FGJSBBase. The relevant
+      enumerators for the vector returned by this call are, ePhi=1, eTht=2, ePsi=3.
+      units radians
+      @return The Euler angle vector, where the first item in the
+              vector is the angle about the X axis, the second is the
+              angle about the Y axis, and the third item is the angle
+              about the Z axis (Phi, Theta, Psi).
+  */
   const FGColumnVector3& GetEuler(void) const { return VState.vQtrn.GetEuler(); }
 
+  /** Retrieves a body frame velocity component.
+      Retrieves a body frame velocity component. The velocity returned is
+      extracted from the vUVW vector (an FGColumnVector). The vector for the
+      velocity in Body frame is organized (Vx, Vy, Vz). The vector is 1-based.
+      In other words, GetUVW(1) returns Vx. Various convenience enumerators
+      are defined in FGJSBBase. The relevant enumerators for the velocity
+      returned by this call are, eX=1, eY=2, eZ=3.
+      units ft/sec
+      @param idx the index of the velocity component desired (1-based).
+      @return The body frame velocity component.
+  */
   double GetUVW   (int idx) const { return VState.vUVW(idx); }
+
+  /** Retrieves a body frame acceleration component.
+      Retrieves a body frame acceleration component. The acceleration returned
+      is extracted from the vUVWdot vector (an FGColumnVector). The vector for
+      the acceleration in Body frame is organized (Ax, Ay, Az). The vector is
+      1-based. In other words, GetUVWdot(1) returns Ax. Various convenience
+      enumerators are defined in FGJSBBase. The relevant enumerators for the
+      acceleration returned by this call are, eX=1, eY=2, eZ=3.
+      units ft/sec^2
+      @param idx the index of the acceleration component desired (1-based).
+      @return The body frame acceleration component.
+  */
   double GetUVWdot(int idx) const { return vUVWdot(idx); }
+
+  /** Retrieves a Local frame velocity component.
+      Retrieves a Local frame velocity component. The velocity returned is
+      extracted from the vVel vector (an FGColumnVector). The vector for the
+      velocity in Local frame is organized (Vnorth, Veast, Vdown). The vector
+      is 1-based. In other words, GetVel(1) returns Vnorth. Various convenience
+      enumerators are defined in FGJSBBase. The relevant enumerators for the
+      velocity returned by this call are, eNorth=1, eEast=2, eDown=3.
+      units ft/sec
+      @param idx the index of the velocity component desired (1-based).
+      @return The body frame velocity component.
+  */
   double GetVel(int idx) const { return vVel(idx); }
+
+  /** Retrieves the total inertial velocity in ft/sec.
+  */
+  double GetInertialVelocityMagnitude(void) const { return vInertialVelocity.Magnitude(); }
+
+  /** Returns the current altitude.
+      Returns the current altitude. Specifically, this function returns the
+      difference between the distance to the center of the Earth, and sea level.
+      units ft
+      @return The current altitude above sea level in feet.
+  */
   double Geth(void)   const { return VState.vLocation.GetRadius() - SeaLevelRadius; }
+
+  /** Returns the current altitude.
+      Returns the curren altitude. Specifically, this function returns the
+      difference between the distance to the center of the Earth, and sea level.
+      units meters
+      @return The current altitude above sea level in meters.
+  */
+  double Gethmeters(void) const { return Geth()*fttom;}
+
+  /** Retrieves a body frame angular velocity component.
+      Retrieves a body frame angular velocity component. The angular velocity
+      returned is extracted from the vPQR vector (an FGColumnVector). The vector
+      for the angular velocity in Body frame is organized (P, Q, R). The vector
+      is 1-based. In other words, GetPQR(1) returns P (roll rate). Various
+      convenience enumerators are defined in FGJSBBase. The relevant enumerators
+      for the angular velocity returned by this call are, eP=1, eQ=2, eR=3.
+      units rad/sec
+      @param axis the index of the angular velocity component desired (1-based).
+      @return The body frame angular velocity component.
+  */
   double GetPQR(int axis) const {return VState.vPQR(axis);}
-  double GetPQRdot(int idx) const {return vPQRdot(idx);}
+
+  /** Retrieves a body frame angular acceleration component.
+      Retrieves a body frame angular acceleration component. The angular
+      acceleration returned is extracted from the vPQRdot vector (an
+      FGColumnVector). The vector for the angular acceleration in Body frame
+      is organized (Pdot, Qdot, Rdot). The vector is 1-based. In other words,
+      GetPQRdot(1) returns Pdot (roll acceleration). Various convenience
+      enumerators are defined in FGJSBBase. The relevant enumerators for the
+      angular acceleration returned by this call are, eP=1, eQ=2, eR=3.
+      units rad/sec^2
+      @param axis the index of the angular acceleration component desired (1-based).
+      @return The body frame angular acceleration component.
+  */
+  double GetPQRdot(int axis) const {return vPQRdot(axis);}
+
+  /** Retrieves a vehicle Euler angle component.
+      Retrieves an Euler angle (Phi, Theta, or Psi) from the quaternion that
+      stores the vehicle orientation relative to the Local frame. The order of
+      rotations used is Yaw-Pitch-Roll. The Euler angle with subscript (1) is
+      Phi. Various convenience enumerators are defined in FGJSBBase. The
+      relevant enumerators for the Euler angle returned by this call are,
+      ePhi=1, eTht=2, ePsi=3 (e.g. GetEuler(eTht) returns Theta).
+      units radians
+      @return An Euler angle.
+  */
   double GetEuler(int axis) const { return VState.vQtrn.GetEuler(axis); }
+
+  /** Retrieves the cosine of a vehicle Euler angle component.
+      Retrieves the cosine of an Euler angle (Phi, Theta, or Psi) from the
+      quaternion that stores the vehicle orientation relative to the Local frame.
+      The order of rotations used is Yaw-Pitch-Roll. The Euler angle
+      with subscript (1) is Phi. Various convenience enumerators are defined in
+      FGJSBBase. The relevant enumerators for the Euler angle referred to in this
+      call are, ePhi=1, eTht=2, ePsi=3 (e.g. GetCosEuler(eTht) returns cos(theta)).
+      units none
+      @return The cosine of an Euler angle.
+  */
   double GetCosEuler(int idx) const { return VState.vQtrn.GetCosEuler(idx); }
+
+  /** Retrieves the sine of a vehicle Euler angle component.
+      Retrieves the sine of an Euler angle (Phi, Theta, or Psi) from the
+      quaternion that stores the vehicle orientation relative to the Local frame.
+      The order of rotations used is Yaw-Pitch-Roll. The Euler angle
+      with subscript (1) is Phi. Various convenience enumerators are defined in
+      FGJSBBase. The relevant enumerators for the Euler angle referred to in this
+      call are, ePhi=1, eTht=2, ePsi=3 (e.g. GetSinEuler(eTht) returns sin(theta)).
+      units none
+      @return The sine of an Euler angle.
+  */
   double GetSinEuler(int idx) const { return VState.vQtrn.GetSinEuler(idx); }
+
+  /** Returns the current altitude rate.
+      Returns the current altitude rate (rate of climb).
+      units ft/sec
+      @return The current rate of change in altitude.
+  */
   double Gethdot(void) const { return -vVel(eDown); }
 
   /** Returns the "constant" RunwayRadius.
       The RunwayRadius parameter is set by the calling application or set to
-      zero if JSBSim is running in standalone mode.
+      sea level if JSBSim is running in standalone mode.
+      units feet
       @return distance of the runway from the center of the earth.
-      @units feet */
+      */
   double GetRunwayRadius(void) const;
+
   double GetSeaLevelRadius(void) const { return SeaLevelRadius; }
+  double GetTerrainElevationASL(void) const;
   double GetDistanceAGL(void)  const;
-  double GetRadius(void) const { return VState.vLocation.GetRadius(); }
+  double GetRadius(void) const {
+      if (VState.vLocation.GetRadius() == 0) return 1.0;
+      else return VState.vLocation.GetRadius();
+  }
   double GetLongitude(void) const { return VState.vLocation.GetLongitude(); }
   double GetLatitude(void) const { return VState.vLocation.GetLatitude(); }
+
+  double GetGeodLatitudeRad(void) const { return VState.vLocation.GetGeodLatitudeRad(); }
+  double GetGeodLatitudeDeg(void) const { return VState.vLocation.GetGeodLatitudeDeg(); }
+
+  double GetGeodeticAltitude(void) const { return VState.vLocation.GetGeodAltitude(); }
+
+  double GetLongitudeDeg(void) const { return VState.vLocation.GetLongitudeDeg(); }
+  double GetLatitudeDeg(void) const { return VState.vLocation.GetLatitudeDeg(); }
   const FGLocation& GetLocation(void) const { return VState.vLocation; }
 
   /** Retrieves the local-to-body transformation matrix.
+      The quaternion class, being the means by which the orientation of the
+      vehicle is stored, manages the local-to-body transformation matrix.
       @return a reference to the local-to-body transformation matrix.  */
   const FGMatrix33& GetTl2b(void) const { return VState.vQtrn.GetT(); }
 
   /** Retrieves the body-to-local transformation matrix.
+      The quaternion class, being the means by which the orientation of the
+      vehicle is stored, manages the body-to-local transformation matrix.
       @return a reference to the body-to-local matrix.  */
   const FGMatrix33& GetTb2l(void) const { return VState.vQtrn.GetTInv(); }
 
+  /** Retrieves the ECEF-to-body transformation matrix.
+      @return a reference to the ECEF-to-body transformation matrix.  */
+  const FGMatrix33& GetTec2b(void) const { return Tec2b; }
+
+  /** Retrieves the body-to-ECEF transformation matrix.
+      @return a reference to the body-to-ECEF matrix.  */
+  const FGMatrix33& GetTb2ec(void) const { return Tb2ec; }
+
+  /** Retrieves the ECEF-to-ECI transformation matrix.
+      @return a reference to the ECEF-to-ECI transformation matrix.  */
+  const FGMatrix33& GetTec2i(void);
+
+  /** Retrieves the ECI-to-ECEF transformation matrix.
+      @return a reference to the ECI-to-ECEF matrix.  */
+  const FGMatrix33& GetTi2ec(void);
+
+  /** Retrieves the ECEF-to-local transformation matrix.
+      Retrieves the ECEF-to-local transformation matrix. Note that the so-called
+      local from is also know as the NED frame (for North, East, Down).
+      @return a reference to the ECEF-to-local matrix.  */
+  const FGMatrix33& GetTec2l(void) const { return VState.vLocation.GetTec2l(); }
+
+  /** Retrieves the local-to-ECEF transformation matrix.
+      Retrieves the local-to-ECEF transformation matrix. Note that the so-called
+      local from is also know as the NED frame (for North, East, Down).
+      @return a reference to the local-to-ECEF matrix.  */
+  const FGMatrix33& GetTl2ec(void) const { return VState.vLocation.GetTl2ec(); }
+
+  const VehicleState GetVState(void) const { return VState; }
+
+  void SetVState(VehicleState vstate) {
+      VState.vLocation = vstate.vLocation;
+      VState.vUVW = vstate.vUVW;
+      VState.vPQR = vstate.vPQR;
+      VState.vQtrn = vstate.vQtrn; // ... mmh
+  }
+
+  const FGQuaternion GetQuaternion(void) const { return VState.vQtrn; }
+
+  void SetPQR(unsigned int i, double val) {
+      if ((i>=1) && (i<=3) )
+          VState.vPQR(i) = val;
+  }
+
+  void SetUVW(unsigned int i, double val) {
+      if ((i>=1) && (i<=3) )
+          VState.vUVW(i) = val;
+  }
+
 // SET functions
 
   void SetLongitude(double lon) { VState.vLocation.SetLongitude(lon); }
+  void SetLongitudeDeg(double lon) {SetLongitude(lon*degtorad);}
   void SetLatitude(double lat) { VState.vLocation.SetLatitude(lat); }
+  void SetLatitudeDeg(double lat) {SetLatitude(lat*degtorad);}
   void SetRadius(double r) { VState.vLocation.SetRadius(r); }
   void SetLocation(const FGLocation& l) { VState.vLocation = l; }
   void Seth(double tt);
+  void Sethmeters(double tt) {Seth(tt/fttom);}
   void SetSeaLevelRadius(double tt) { SeaLevelRadius = tt; }
+  void SetTerrainElevationASL(double tt);
   void SetDistanceAGL(double tt);
   void SetInitialState(const FGInitialCondition *);
   void RecomputeRunwayRadius(void);
 
-  void bind(void);
-  void unbind(void);
+  void CalculatePQRdot(void);
+  void CalculateQuatdot(void);
+  void CalculateLocationdot(void);
+  void CalculateUVWdot(void);
 
 private:
 
@@ -154,13 +472,34 @@ private:
   struct VehicleState VState;
 
   FGColumnVector3 vVel;
+  FGColumnVector3 vInertialVelocity;
   FGColumnVector3 vPQRdot, last_vPQRdot, last2_vPQRdot;
   FGColumnVector3 vUVWdot, last_vUVWdot, last2_vUVWdot;
   FGColumnVector3 vLocationDot, last_vLocationDot, last2_vLocationDot;
+  FGColumnVector3 vLocation;
+  FGColumnVector3 vPQRi;   // Inertial frame angular velocity
+  FGColumnVector3 vOmega;  // The Earth angular velocity vector
+  FGColumnVector3 vOmegaLocal;  // The local frame angular velocity vector
   FGQuaternion vQtrndot, last_vQtrndot, last2_vQtrndot;
+  FGMatrix33 Tec2b;
+  FGMatrix33 Tb2ec;
+  FGMatrix33 Tl2b;   // local to body frame matrix copy for immediate local use
+  FGMatrix33 Tb2l;   // body to local frame matrix copy for immediate local use
+  FGMatrix33 Tl2ec;  // local to ECEF matrix copy for immediate local use
+  FGMatrix33 Tec2l;  // ECEF to local frame matrix copy for immediate local use
+  FGMatrix33 Tec2i;  // ECEF to ECI frame matrix copy for immediate local use
+  FGMatrix33 Ti2ec;  // ECI to ECEF frame matrix copy for immediate local use
+  FGMatrix33 Ti2b;   // ECI to body frame rotation matrix
+  FGMatrix33 Tb2i;   // body to ECI frame rotation matrix
   
-  double RunwayRadius, SeaLevelRadius;
+  double RunwayRadius, SeaLevelRadius, VehicleRadius;
+  double radInv;
+  int integrator_rotational_rate;
+  int integrator_translational_rate;
+  int integrator_rotational_position;
+  int integrator_translational_position;
 
+  void bind(void);
   void Debug(int from);
 };
 }
index a6f45021fb8a3d2972cc66a5ee9ef389dff78fa4..aff448a591ad2ed6138a0360d669fb52ab75ed90 100644 (file)
@@ -71,12 +71,14 @@ FGPropulsion::FGPropulsion(FGFDMExec* exec) : FGModel(exec)
 {
   Name = "FGPropulsion";
 
+  InitializedEngines = 0;
   numSelectedFuelTanks = numSelectedOxiTanks = 0;
   numTanks = numEngines = 0;
   numOxiTanks = numFuelTanks = 0;
   ActiveEngine = -1; // -1: ALL, 0: Engine 1, 1: Engine 2 ...
   tankJ.InitMatrix();
-  refuel = false;
+  refuel = dump = false;
+  DumpRate = 0.0;
   fuel_freeze = false;
   TotalFuelQuantity = 0.0;
   IsBound =
@@ -85,6 +87,7 @@ FGPropulsion::FGPropulsion(FGFDMExec* exec) : FGModel(exec)
   HaveRocketEngine =
   HaveTurboPropEngine =
   HaveElectricEngine = false;
+  HasInitializedEngines = false;
 
   Debug(0);
 }
@@ -95,12 +98,39 @@ FGPropulsion::~FGPropulsion()
 {
   for (unsigned int i=0; i<Engines.size(); i++) delete Engines[i];
   Engines.clear();
-  unbind();
+  for (unsigned int i=0; i<Tanks.size(); i++) delete Tanks[i];
+  Tanks.clear();
   Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+bool FGPropulsion::InitModel(void)
+{
+  if (!FGModel::InitModel()) return false;
+
+  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:
+        ((FGPiston*)Engines[i])->ResetToIC();
+        if (HasInitializedEngines && (InitializedEngines & i)) InitRunning(i);
+        break;
+      case FGEngine::etTurbine:
+        ((FGTurbine*)Engines[i])->ResetToIC();
+        if (HasInitializedEngines && (InitializedEngines & i)) InitRunning(i);
+        break;
+      default:
+        break;
+    }
+  }
+
+  return true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 bool FGPropulsion::Run(void)
 {
   unsigned int i;
@@ -128,6 +158,7 @@ bool FGPropulsion::Run(void)
   }
 
   if (refuel) DoRefuel( dt * rate );
+  if (dump) DumpFuel( dt * rate );
 
   return false;
 }
@@ -145,21 +176,29 @@ bool FGPropulsion::GetSteadyState(void)
 
   if (!FGModel::Run()) {
     for (unsigned int i=0; i<numEngines; i++) {
+      cout << "  Finding steady state for engine " << i << endl;
       Engines[i]->SetTrimMode(true);
       steady=false;
       steady_count=0;
+      j=0;
       while (!steady && j < 6000) {
         Engines[i]->Calculate();
         lastThrust = currentThrust;
         currentThrust = Engines[i]->GetThrust();
         if (fabs(lastThrust-currentThrust) < 0.0001) {
           steady_count++;
-          if (steady_count > 120) { steady=true; }
+          if (steady_count > 120) {
+            steady=true;
+            cout << "    Steady state found at thrust: " << currentThrust << " lbs." << endl;
+          }
         } else {
           steady_count=0;
         }
         j++;
       }
+      if (j >= 6000) {
+        cout << "    Could not find a steady state for this engine." << endl;
+      }
       vForces  += Engines[i]->GetBodyForces();  // sum body frame forces
       vMoments += Engines[i]->GetMoments();     // sum body frame moments
       Engines[i]->SetTrimMode(false);
@@ -173,25 +212,36 @@ bool FGPropulsion::GetSteadyState(void)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-bool FGPropulsion::ICEngineStart(void)
+void FGPropulsion::InitRunning(int n)
 {
-  int j;
+  if (n > 0) { // A specific engine is supposed to be initialized
 
-  vForces.InitMatrix();
-  vMoments.InitMatrix();
+    if (n >= GetNumEngines() ) {
+      cerr << "Tried to initialize a non-existent engine!" << endl;
+      throw;
+    }
+    FCS->SetThrottleCmd(n,1);
+    FCS->SetMixtureCmd(n,1);
+    GetEngine(n)->InitRunning();
+    GetSteadyState();
 
-  for (unsigned int i=0; i<numEngines; i++) {
-    Engines[i]->SetTrimMode(true);
-    j=0;
-    while (!Engines[i]->GetRunning() && j < 2000) {
-      Engines[i]->Calculate();
-      j++;
+    InitializedEngines = 1 << n;
+    HasInitializedEngines = true;
+
+  } else if (n < 0) { // -1 refers to "All Engines"
+
+    for (unsigned int i=0; i<GetNumEngines(); i++) {
+      FCS->SetThrottleCmd(i,1);
+      FCS->SetMixtureCmd(i,1);
+      GetEngine(i)->InitRunning();
     }
-    vForces  += Engines[i]->GetBodyForces();  // sum body frame forces
-    vMoments += Engines[i]->GetMoments();     // sum body frame moments
-    Engines[i]->SetTrimMode(false);
+    GetSteadyState();
+    InitializedEngines = -1;
+    HasInitializedEngines = true;
+
+  } else if (n == 0) { // No engines are to be initialized
+    // Do nothing
   }
-  return true;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -255,7 +305,7 @@ bool FGPropulsion::Load(Element* el)
 
   Element* tank_element = el->FindElement("tank");
   while (tank_element) {
-    Tanks.push_back(new FGTank(FDMExec, tank_element));
+    Tanks.push_back(new FGTank(FDMExec, tank_element, numTanks));
     if (Tanks.back()->GetType() == FGTank::ttFUEL) numFuelTanks++;
     else if (Tanks.back()->GetType() == FGTank::ttOXIDIZER) numOxiTanks++;
     else {cerr << "Unknown tank type specified." << endl; return false;}
@@ -268,6 +318,11 @@ bool FGPropulsion::Load(Element* el)
   CalculateTankInertias();
   if (!ThrottleAdded) FCS->AddThrottle(); // need to have at least one throttle
 
+  // Process fuel dump rate
+  if (el->FindElement("dump-rate"))
+    DumpRate = el->FindElementValueAsNumberConvertTo("dump-rate", "LBS/MIN");
+
+
   return true;
 }
 
@@ -278,7 +333,7 @@ string FGPropulsion::FindEngineFullPathname(string engine_filename)
   string fullpath, localpath;
   string enginePath = FDMExec->GetEnginePath();
   string aircraftPath = FDMExec->GetFullAircraftPath();
-  ifstream* engine_file = new ifstream();
+  ifstream engine_file;
 
   string separator = "/";
 # ifdef macintosh
@@ -288,10 +343,10 @@ string FGPropulsion::FindEngineFullPathname(string engine_filename)
   fullpath = enginePath + separator;
   localpath = aircraftPath + separator + "Engines" + separator;
 
-  engine_file->open(string(fullpath + engine_filename + ".xml").c_str());
-  if ( !engine_file->is_open()) {
-    engine_file->open(string(localpath + engine_filename + ".xml").c_str());
-      if ( !engine_file->is_open()) {
+  engine_file.open(string(fullpath + engine_filename + ".xml").c_str());
+  if ( !engine_file.is_open()) {
+    engine_file.open(string(localpath + engine_filename + ".xml").c_str());
+      if ( !engine_file.is_open()) {
         cerr << " Could not open engine file: " << engine_filename << " in path "
              << fullpath << " or " << localpath << endl;
         return string("");
@@ -382,13 +437,11 @@ string FGPropulsion::GetPropulsionValues(string delimeter)
 
 FGColumnVector3& FGPropulsion::GetTanksMoment(void)
 {
-  iTank = Tanks.begin();
   vXYZtank_arm.InitMatrix();
-  while (iTank < Tanks.end()) {
-    vXYZtank_arm(eX) += (*iTank)->GetXYZ(eX)*(*iTank)->GetContents();
-    vXYZtank_arm(eY) += (*iTank)->GetXYZ(eY)*(*iTank)->GetContents();
-    vXYZtank_arm(eZ) += (*iTank)->GetXYZ(eZ)*(*iTank)->GetContents();
-    iTank++;
+  for (unsigned int i=0; i<Tanks.size(); i++) {
+    vXYZtank_arm(eX) += Tanks[i]->GetXYZ(eX) * Tanks[i]->GetContents();
+    vXYZtank_arm(eY) += Tanks[i]->GetXYZ(eY) * Tanks[i]->GetContents();
+    vXYZtank_arm(eZ) += Tanks[i]->GetXYZ(eZ) * Tanks[i]->GetContents();
   }
   return vXYZtank_arm;
 }
@@ -399,11 +452,8 @@ double FGPropulsion::GetTanksWeight(void)
 {
   double Tw = 0.0;
 
-  iTank = Tanks.begin();
-  while (iTank < Tanks.end()) {
-    Tw += (*iTank)->GetContents();
-    iTank++;
-  }
+  for (unsigned int i=0; i<Tanks.size(); i++) Tw += Tanks[i]->GetContents();
+
   return Tw;
 }
 
@@ -531,6 +581,28 @@ void FGPropulsion::DoRefuel(double time_slice)
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGPropulsion::DumpFuel(double time_slice)
+{
+  unsigned int i;
+  int TanksDumping = 0;
+
+  for (i=0; i<numTanks; i++) {
+    if (Tanks[i]->GetContents() > Tanks[i]->GetStandpipe()) ++TanksDumping;
+  }
+
+  if (TanksDumping == 0) return;
+
+  double dump_rate_per_tank = DumpRate / 60.0 * time_slice / TanksDumping;
+
+  for (i=0; i<numTanks; i++) {
+    if (Tanks[i]->GetContents() > Tanks[i]->GetStandpipe()) {
+      Transfer(i, -1, dump_rate_per_tank);
+    }
+  }
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 void FGPropulsion::SetFuelFreeze(bool f)
 {
   fuel_freeze = f;
@@ -547,7 +619,7 @@ void FGPropulsion::bind(void)
   typedef int (FGPropulsion::*iPMF)(void) const;
 
   IsBound = true;
-
+  PropertyManager->Tie("propulsion/set-running", this, (iPMF)0, &FGPropulsion::InitRunning, true);
   if (HaveTurbineEngine) {
     PropertyManager->Tie("propulsion/starter_cmd", this, (iPMF)0, &FGPropulsion::SetStarter,  true);
     PropertyManager->Tie("propulsion/cutoff_cmd", this,  (iPMF)0, &FGPropulsion::SetCutoff,   true);
@@ -561,24 +633,23 @@ void FGPropulsion::bind(void)
   PropertyManager->Tie("propulsion/active_engine", this, (iPMF)&FGPropulsion::GetActiveEngine,
                         &FGPropulsion::SetActiveEngine, true);
   PropertyManager->Tie("propulsion/total-fuel-lbs", this, &FGPropulsion::GetTotalFuelQuantity);
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGPropulsion::unbind(void)
-{
-  if (!IsBound) return;
+  PropertyManager->Tie("propulsion/refuel", this, &FGPropulsion::GetRefuel,
+                        &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);
 
-  if (HaveTurbineEngine) {
-    PropertyManager->Untie("propulsion/starter_cmd");
-    PropertyManager->Untie("propulsion/cutoff_cmd");
-  }
-  if (HavePistonEngine) {
-    PropertyManager->Untie("propulsion/starter_cmd");
-    PropertyManager->Untie("propulsion/magneto_cmd");
-  }
-  PropertyManager->Untie("propulsion/active_engine");
-  PropertyManager->Untie("propulsion/total-fuel-lbs");
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index 9884f61c34ead2be26452f3f89e05cd500248d25..71351477e721b0b6b9d1033d67fb102b73a63ea3 100644 (file)
@@ -42,16 +42,13 @@ INCLUDES
 #  include <simgear/compiler.h>
 #  ifdef SG_HAVE_STD_INCLUDES
 #    include <vector>
-#    include <iterator>
 #    include <fstream>
 #  else
 #    include <vector.h>
-#    include <iterator.h>
 #    include <fstream.h>
 #  endif
 #else
 #  include <vector>
-#  include <iterator>
 #  include <fstream>
 #endif
 
@@ -80,12 +77,29 @@ CLASS DOCUMENTATION
 /** Propulsion management class.
     The Propulsion class is the container for the entire propulsion system, which is
     comprised of engines, and tanks. Once the Propulsion class gets the config file,
-    it reads in information which is specific to a type of engine. Then:
+    it reads in the \<propulsion> section. Then:
 
     -# The appropriate engine type instance is created
     -# At least one tank object is created, and is linked to an engine.
 
-    At Run time each engines Calculate() method is called.
+    At Run time each engine's Calculate() method is called.
+
+    <h3>Configuration File Format:</h3>
+
+  @code
+    <propulsion>
+        <engine file="{string}">
+          ... see FGEngine, FGThruster, and class for engine type ...
+        </engine>
+        ... more engines ...
+        <tank type="{FUEL | OXIDIZER}"> 
+          ... see FGTank ...
+        </tank>
+        ... more tanks ...
+        <dump-rate unit="{LBS/MIN | KG/MIN}"> {number} </dump-rate>
+    </propulsion>
+  @endcode
+
     @author Jon S. Berndt
     @version $Id$
     @see
@@ -112,6 +126,8 @@ public:
       [Note: Should we be checking the Starved flag here?] */
   bool Run(void);
 
+  bool InitModel(void);
+
   /** Loads the propulsion system (engine[s] and tank[s]).
       Characteristics of the propulsion system are read in from the config file.
       @param el pointer to an XML element that contains the engine information.
@@ -149,9 +165,8 @@ public:
   /** Loops the engines until thrust output steady (used for trimming) */
   bool GetSteadyState(void);
 
-  /** starts the engines in IC mode (dt=0).  All engine-specific setup must
-      be done before calling this (i.e. magnetos, starter engage, etc.) */
-  bool ICEngineStart(void);
+  /** Sets up the engines as running */
+  void InitRunning(int n);
 
   string GetPropulsionStrings(string delimeter);
   string GetPropulsionValues(string delimeter);
@@ -161,10 +176,13 @@ public:
   inline FGColumnVector3& GetMoments(void) {return vMoments;}
   inline double GetMoments(int n) const {return vMoments(n);}
 
-  inline bool GetRefuel(void) {return refuel;}
+  inline bool GetRefuel(void) const {return refuel;}
   inline void SetRefuel(bool setting) {refuel = setting;}
+  inline bool GetFuelDump(void) const {return dump;}
+  inline void SetFuelDump(bool setting) {dump = setting;}
   double Transfer(int source, int target, double amount);
   void DoRefuel(double time_slice);
+  void DumpFuel(double time_slice);
 
   FGColumnVector3& GetTanksMoment(void);
   double GetTanksWeight(void);
@@ -182,13 +200,9 @@ public:
   void SetFuelFreeze(bool f);
   FGMatrix33& CalculateTankInertias(void);
 
-  void bind();
-  void unbind();
-
 private:
   vector <FGEngine*>   Engines;
   vector <FGTank*>     Tanks;
-  vector <FGTank*>::iterator iTank;
   unsigned int numSelectedFuelTanks;
   unsigned int numSelectedOxiTanks;
   unsigned int numFuelTanks;
@@ -202,8 +216,10 @@ private:
   FGColumnVector3 vXYZtank_arm;
   FGMatrix33 tankJ;
   bool refuel;
+  bool dump;
   bool fuel_freeze;
   double TotalFuelQuantity;
+  double DumpRate;
   bool IsBound;
   bool HavePistonEngine;
   bool HaveTurbineEngine;
@@ -211,6 +227,10 @@ private:
   bool HaveRocketEngine;
   bool HaveElectricEngine;
 
+  int InitializedEngines;
+  bool HasInitializedEngines;
+
+  void bind();
   void Debug(int from);
 };
 }
index 10c65a77e032f4a01cd401f7be913463d90e86a9..6a7a7e932e6323e0c509596dcb683260a0204957 100644 (file)
@@ -3,12 +3,16 @@ SUBDIRS = atmosphere propulsion flight_control
 noinst_LIBRARIES = libModels.a
 
 libModels_a_SOURCES = FGAerodynamics.cpp FGAircraft.cpp FGAtmosphere.cpp \
-                      FGAuxiliary.cpp FGFCS.cpp FGGroundReactions.cpp FGInertial.cpp \
+                      FGAuxiliary.cpp FGFCS.cpp FGGroundReactions.cpp \
+                      FGInertial.cpp FGBuoyantForces.cpp FGExternalForce.cpp \
                       FGLGear.cpp FGMassBalance.cpp FGModel.cpp FGOutput.cpp \
-                      FGPropagate.cpp FGPropulsion.cpp FGInput.cpp
+                      FGPropagate.cpp FGPropulsion.cpp FGInput.cpp \
+                      FGExternalReactions.cpp FGGasCell.cpp
 
 noinst_HEADERS = FGAerodynamics.h FGAircraft.h FGAtmosphere.h FGAuxiliary.h \
-                 FGFCS.h FGGroundReactions.h FGInertial.h FGLGear.h FGMassBalance.h \
-                 FGModel.h FGOutput.h FGPropagate.h FGPropulsion.h FGInput.h 
+                 FGFCS.h FGGroundReactions.h FGInertial.h FGLGear.h \
+                 FGMassBalance.h FGBuoyantForces.h FGExternalForce.h \
+                 FGModel.h FGOutput.h FGPropagate.h FGPropulsion.h FGInput.h \
+                 FGExternalReactions.h FGGasCell.h
 
 INCLUDES = -I$(top_srcdir)/src/FDM/JSBSim
index 2c86c6ddf04fd428548b59904b797b74f93560c3..f5079f99e1309fbf0d55d62436774f21a93c2611 100755 (executable)
@@ -103,7 +103,6 @@ MSIS::MSIS(FGFDMExec* fdmex) : FGAtmosphere(fdmex)
 
 MSIS::~MSIS()
 {
-  unbind();
   Debug(1);
 }
 
index 848455d5cdc3e59fecb13d0d33516e8312bfdf1c..544484587106dee10fc798054d381f6b68aa1955 100755 (executable)
@@ -80,7 +80,6 @@ FGMars::FGMars(FGFDMExec* fdmex) : FGAtmosphere(fdmex)
 /*
 FGMars::~FGMars()
 {
-  unbind();
   Debug(1);
 }
 */
index 3a06e89b33656d0dad7ee1ef46b2058d8d947813..fd556aa6fab5998d2a26e14b49a6ccdfa84f6cfe 100755 (executable)
@@ -104,11 +104,17 @@ bool FGActuator::Run(void )
   dt = fcs->GetDt();
 
   Input = InputNodes[0]->getDoubleValue() * InputSigns[0];
-  Output = Input; // perfect actuator
 
   if (fail_zero) Input = 0;
   if (fail_hardover) Input =  clipmax*fabs(Input)/Input;
 
+  Output = Input; // Perfect actuator. At this point, if no failures are present
+                  // and no subsequent lag, limiting, etc. is done, the output
+                  // is simply the input. If any further processing is done
+                  // (below) such as lag, rate limiting, hysteresis, etc., then
+                  // the Input will be further processed and the eventual Output
+                  // will be overwritten from this perfect value.
+
   if (lag != 0.0)              Lag();        // models actuator lag
   if (rate_limit != 0)         RateLimit();  // limit the actuator rate
   if (deadband_width != 0.0)   Deadband();
index a420cbec998e4d2d087e12a88310a9c36418d2ca..e7407f33375bec06c390cba087d24c091d906b3e 100755 (executable)
@@ -65,12 +65,12 @@ CLASS DOCUMENTATION
     applied to the actuator. In order of application to the input signal,
     these are:
     
-    -System lag (input lag, really)
-    -Rate limiting
-    -Deadband
-    -Hysteresis (mechanical hysteresis)
-    -Bias (mechanical bias)
-    -Position limiting ("hard stops")
+    - System lag (input lag, really)
+    - Rate limiting
+    - Deadband
+    - Hysteresis (mechanical hysteresis)
+    - Bias (mechanical bias)
+    - Position limiting ("hard stops")
     
     There are also several malfunctions that can be applied to the actuator
     by setting a property to true or false (or 1 or 0).
@@ -78,7 +78,7 @@ CLASS DOCUMENTATION
 Syntax:
 
 @code
-<actuator name=\94name\94>
+<actuator name="name">
   <input> {[-]property} </input>
   <lag> number </lag>
   <rate_limit> number <rate_limit>
@@ -96,7 +96,7 @@ Syntax:
 Example:
 
 @code
-<actuator name=\94fcs/gimbal_pitch_position\94>
+<actuator name="fcs/gimbal_pitch_position">
   <input> fcs/gimbal_pitch_command </input>
   <lag> 60 </lag>
   <rate_limit> 0.085 <rate_limit> <!-- 5 degrees/sec -->
index 4bdb8108eb151e0b1592e3274ff3993404e3b282..6f458d16187cff5a991f01cbd3075ce4fe406cc5 100644 (file)
@@ -123,8 +123,6 @@ void FGDeadBand::Debug(int from)
       cout << "      INPUT: " << InputNodes[0]->getName() << endl;
       cout << "      DEADBAND WIDTH: " << width << endl;
       cout << "      GAIN: " << gain << endl;
-      if (clip) cout << "      CLIPTO: " << clipmin
-                                  << ", " << clipmax << endl;
       if (IsOutput) cout << "      OUTPUT: " << OutputNode->getName() << endl;
     }
   }
index 471e5ab0d224263f9525b168613316ccd0b9f014..8f8b595b57a5983a517c36f2fd5bba4b028964ed 100644 (file)
@@ -59,7 +59,7 @@ CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 /** Models a deadband object.
-    This is a component that allows for some \93play\94 in a control path, in the
+    This is a component that allows for some "play" in a control path, in the
     form of a dead zone, or deadband. The form of the deadband component
     specification is:
 
@@ -77,7 +77,7 @@ CLASS DOCUMENTATION
 
     The width value is the total deadband region within which an input will
     produce no output. For example, say that the width value is 2.0. If the
-    input is between \961.0 and +1.0, the output will be zero.
+    input is between -1.0 and +1.0, the output will be zero.
     @author Jon S. Berndt
     @version $Id$
 */
index b7f31b6d39c26ac2d0579e8b8429994b832ee205..26f73facf2f4cb33560ef4d047be6ef251503ac3 100644 (file)
@@ -113,7 +113,7 @@ FGFCSComponent::FGFCSComponent(FGFCS* _fcs, Element* element) : fcs(_fcs)
       InputNodes.push_back( tmp );
     } else {
       cerr << fgred << "  In component: " << Name << " unknown property "
-           << input << " referenced. Aborting" << endl;
+           << input << " referenced. Aborting" << reset << endl;
       exit(-1);
     }
     input_element = element->FindNextElement("input");
@@ -121,7 +121,7 @@ FGFCSComponent::FGFCSComponent(FGFCS* _fcs, Element* element) : fcs(_fcs)
 
   if (element->FindElement("output")) {
     IsOutput = true;
-    OutputNode = PropertyManager->GetNode( element->FindElementValue("output") );
+    OutputNode = PropertyManager->GetNode( element->FindElementValue("output"), true );
     if (!OutputNode) {
       cerr << endl << "  Unable to process property: " << element->FindElementValue("output") << endl;
       throw(string("Invalid output property name in flight control definition"));
@@ -132,14 +132,20 @@ FGFCSComponent::FGFCSComponent(FGFCS* _fcs, Element* element) : fcs(_fcs)
   if (clip_el) {
     clip_string = clip_el->FindElementValue("min");
     if (clip_string.find_first_not_of("+-.0123456789") != string::npos) { // it's a property
-      if (clip_string[0] == '-') clipMinSign = -1.0;
+      if (clip_string[0] == '-') {
+        clipMinSign = -1.0;
+        clip_string.erase(0,1);
+      }
       ClipMinPropertyNode = PropertyManager->GetNode( clip_string );
     } else {
       clipmin = clip_el->FindElementValueAsNumber("min");
     }
     clip_string = clip_el->FindElementValue("max");
     if (clip_string.find_first_not_of("+-.0123456789") != string::npos) { // it's a property
-      if (clip_string[0] == '-') clipMaxSign = -1.0;
+      if (clip_string[0] == '-') {
+        clipMaxSign = -1.0;
+        clip_string.erase(0,1);
+      }
       ClipMaxPropertyNode = PropertyManager->GetNode( clip_string );
     } else {
       clipmax = clip_el->FindElementValueAsNumber("max");
@@ -223,12 +229,31 @@ void FGFCSComponent::bind(void)
 
 void FGFCSComponent::Debug(int from)
 {
+  string propsign="";
+
   if (debug_lvl <= 0) return;
 
   if (debug_lvl & 1) { // Standard console startup message output
     if (from == 0) {
       cout << endl << "    Loading Component \"" << Name
                    << "\" of type: " << Type << endl;
+
+      if (clip) {
+        if (ClipMinPropertyNode != 0L) {
+          if (clipMinSign < 0.0) propsign="-";
+          cout << "      Minimum limit: " << propsign << ClipMinPropertyNode->GetName() << endl;
+          propsign="";
+        } else {
+          cout << "      Minimum limit: " << clipmin << endl;
+        }
+        if (ClipMaxPropertyNode != 0L) {
+          if (clipMaxSign < 0.0) propsign="-";
+          cout << "      Maximum limit: " << propsign << ClipMaxPropertyNode->GetName() << endl;
+          propsign="";
+        } else {
+          cout << "      Maximum limit: " << clipmax << endl;
+        }
+      }  
     }
   }
   if (debug_lvl & 2 ) { // Instantiation/Destruction notification
index b47aed33302b4dd7b04986ba8db1c1e219225f34..ea86d4114c2d7ea1c11dc27275154fdc8b8de0d6 100755 (executable)
@@ -69,6 +69,7 @@ FGFCSFunction::FGFCSFunction(FGFCS* fcs, Element* element) : FGFCSComponent(fcs,
 
 FGFCSFunction::~FGFCSFunction()
 {
+  delete function;
   Debug(1);
 }
 
@@ -118,8 +119,6 @@ void FGFCSFunction::Debug(int from)
       if (InputNodes.size()>0)
         cout << "      INPUT: " << InputNodes[0]->getName() << endl;
 //    cout << "      Function: " << endl;
-      if (clip) cout << "      CLIPTO: " << clipmin
-                                  << ", " << clipmax << endl;
       if (IsOutput) cout << "      OUTPUT: " << OutputNode->getName() << endl;
     }
   }
index c189ff64b72a84d4968b0155aeb3a172bf376d23..422d0b0930e9bead004bc09759b82ac32f0d420c 100755 (executable)
@@ -64,13 +64,14 @@ CLASS DOCUMENTATION
 
 One of the most recent additions to the FCS component set is the FCS Function
 component. This component allows a function to be created when no other component
-is suitable. The function component is defined as follows:
+is suitable. Available mathematical operations are described in the FGFunction class.  
+The function component is defined as follows:
 
 @code
 <fcs_function name="Windup Trigger">
   [<input> [-]property </input>]
   <function>
-    \85
+    ...
   </function>
   [<clipto>
     <min> {[-]property name | value} </min>
@@ -81,7 +82,7 @@ is suitable. The function component is defined as follows:
 @endcode
 
 The function definition itself can include a nested series of products, sums,
-quotients, etc. as well as trig and other math functions. Here\92s an example of
+quotients, etc. as well as trig and other math functions. Here's an example of
 a function (from an aero specification):
 
 @code
@@ -103,6 +104,7 @@ a function (from an aero specification):
     </product>
 </function>
 @endcode
+
     @version $Id$
 */
 
index c4437e41cd88c80057cc27fbfabf2a8b6aed9853..d6b263a2dfa6f30c4bf6a203ef38261baf99f731 100644 (file)
@@ -50,12 +50,15 @@ CLASS IMPLEMENTATION
 
 FGFilter::FGFilter(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
 {
-  double denom;
-
   dt = fcs->GetState()->Getdt();
   Trigger = 0;
+  DynamicFilter = false;
 
-  C1 = C2 = C3 = C4 = C5 = C6 = 0.0;
+  C[1] = C[2] = C[3] = C[4] = C[5] = C[6] = 0.0;
+  for (int i=0; i<7; i++) {
+    PropertySign[i] = 1.0;
+    PropertyNode[i] = 0L;
+  }
 
   if      (Type == "LAG_FILTER")          FilterType = eLag        ;
   else if (Type == "LEAD_LAG_FILTER")     FilterType = eLeadLag    ;
@@ -64,60 +67,112 @@ FGFilter::FGFilter(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
   else if (Type == "INTEGRATOR")          FilterType = eIntegrator ;
   else                                    FilterType = eUnknown    ;
 
-  if (element->FindElement("c1")) C1 = element->FindElementValueAsNumber("c1");
-  if (element->FindElement("c2")) C2 = element->FindElementValueAsNumber("c2");
-  if (element->FindElement("c3")) C3 = element->FindElementValueAsNumber("c3");
-  if (element->FindElement("c4")) C4 = element->FindElementValueAsNumber("c4");
-  if (element->FindElement("c5")) C5 = element->FindElementValueAsNumber("c5");
-  if (element->FindElement("c6")) C6 = element->FindElementValueAsNumber("c6");
+  ReadFilterCoefficients(element, 1);
+  ReadFilterCoefficients(element, 2);
+  ReadFilterCoefficients(element, 3);
+  ReadFilterCoefficients(element, 4);
+  ReadFilterCoefficients(element, 5);
+  ReadFilterCoefficients(element, 6);
+
   if (element->FindElement("trigger")) {
     Trigger =  PropertyManager->GetNode(element->FindElementValue("trigger"));
   }
 
   Initialize = true;
 
+  CalculateDynamicFilters();
+
+  FGFCSComponent::bind();
+
+  Debug(0);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+FGFilter::~FGFilter()
+{
+  Debug(1);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGFilter::ReadFilterCoefficients(Element* element, int index)
+{
+  char buf[3];
+  sprintf(buf, "c%d", index);
+  string coefficient = string(buf);
+  string property_string="";
+
+  if ( element->FindElement(coefficient) ) {
+    property_string = element->FindElementValue(coefficient);
+    if (property_string.find_first_not_of("+-.0123456789Ee") != string::npos) { // property
+      if (property_string[0] == '-') {
+       PropertySign[index] = -1.0;
+       property_string.erase(0,1);
+      } else {
+       PropertySign[index] = 1.0;
+      }
+      PropertyNode[index] = PropertyManager->GetNode(property_string);
+      DynamicFilter = true;
+    } else {
+      C[index] = element->FindElementValueAsNumber(coefficient);
+    }
+  }
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGFilter::CalculateDynamicFilters(void)
+{
+  double denom;
+
   switch (FilterType) {
     case eLag:
-      denom = 2.00 + dt*C1;
-      ca = dt*C1 / denom;
-      cb = (2.00 - dt*C1) / denom;
+      if (PropertyNode[1] != 0L) C[1] = PropertyNode[1]->getDoubleValue()*PropertySign[1];
+      denom = 2.00 + dt*C[1];
+      ca = dt*C[1] / denom;
+      cb = (2.00 - dt*C[1]) / denom;
+
       break;
     case eLeadLag:
-      denom = 2.00*C3 + dt*C4;
-      ca = (2.00*C1 + dt*C2) / denom;
-      cb = (dt*C2 - 2.00*C1) / denom;
-      cc = (2.00*C3 - dt*C4) / denom;
+      if (PropertyNode[1] != 0L) C[1] = PropertyNode[1]->getDoubleValue()*PropertySign[1];
+      if (PropertyNode[2] != 0L) C[2] = PropertyNode[2]->getDoubleValue()*PropertySign[2];
+      if (PropertyNode[3] != 0L) C[3] = PropertyNode[3]->getDoubleValue()*PropertySign[3];
+      if (PropertyNode[4] != 0L) C[4] = PropertyNode[4]->getDoubleValue()*PropertySign[4];
+      denom = 2.00*C[3] + dt*C[4];
+      ca = (2.00*C[1] + dt*C[2]) / denom;
+      cb = (dt*C[2] - 2.00*C[1]) / denom;
+      cc = (2.00*C[3] - dt*C[4]) / denom;
       break;
     case eOrder2:
-      denom = 4.0*C4 + 2.0*C5*dt + C6*dt*dt;
-      ca = (4.0*C1 + 2.0*C2*dt + C3*dt*dt) / denom;
-      cb = (2.0*C3*dt*dt - 8.0*C1) / denom;
-      cc = (4.0*C1 - 2.0*C2*dt + C3*dt*dt) / denom;
-      cd = (2.0*C6*dt*dt - 8.0*C4) / denom;
-      ce = (4.0*C4 - 2.0*C5*dt + C6*dt*dt) / denom;
+      if (PropertyNode[1] != 0L) C[1] = PropertyNode[1]->getDoubleValue()*PropertySign[1];
+      if (PropertyNode[2] != 0L) C[2] = PropertyNode[2]->getDoubleValue()*PropertySign[2];
+      if (PropertyNode[3] != 0L) C[3] = PropertyNode[3]->getDoubleValue()*PropertySign[3];
+      if (PropertyNode[4] != 0L) C[4] = PropertyNode[4]->getDoubleValue()*PropertySign[4];
+      if (PropertyNode[5] != 0L) C[5] = PropertyNode[5]->getDoubleValue()*PropertySign[5];
+      if (PropertyNode[6] != 0L) C[6] = PropertyNode[6]->getDoubleValue()*PropertySign[6];
+      denom = 4.0*C[4] + 2.0*C[5]*dt + C[6]*dt*dt;
+      ca = (4.0*C[1] + 2.0*C[2]*dt + C[3]*dt*dt) / denom;
+      cb = (2.0*C[3]*dt*dt - 8.0*C[1]) / denom;
+      cc = (4.0*C[1] - 2.0*C[2]*dt + C[3]*dt*dt) / denom;
+      cd = (2.0*C[6]*dt*dt - 8.0*C[4]) / denom;
+      ce = (4.0*C[4] - 2.0*C[5]*dt + C[6]*dt*dt) / denom;
       break;
     case eWashout:
-      denom = 2.00 + dt*C1;
+      if (PropertyNode[1] != 0L) C[1] = PropertyNode[1]->getDoubleValue()*PropertySign[1];
+      denom = 2.00 + dt*C[1];
       ca = 2.00 / denom;
-      cb = (2.00 - dt*C1) / denom;
+      cb = (2.00 - dt*C[1]) / denom;
       break;
     case eIntegrator:
-      ca = dt*C1 / 2.00;
+      if (PropertyNode[1] != 0L) C[1] = PropertyNode[1]->getDoubleValue()*PropertySign[1];
+      ca = dt*C[1] / 2.00;
       break;
     case eUnknown:
       cerr << "Unknown filter type" << endl;
     break;
   }
-  FGFCSComponent::bind();
-
-  Debug(0);
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-FGFilter::~FGFilter()
-{
-  Debug(1);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -134,6 +189,9 @@ bool FGFilter::Run(void)
   } else {
 
     Input = InputNodes[0]->getDoubleValue() * InputSigns[0];
+    
+    if (DynamicFilter) CalculateDynamicFilters();
+    
     switch (FilterType) {
       case eLag:
         Output = Input * ca + PreviousInput1 * ca + PreviousOutput1 * cb;
@@ -195,17 +253,77 @@ bool FGFilter::Run(void)
 
 void FGFilter::Debug(int from)
 {
+  string sgn="";
+
   if (debug_lvl <= 0) return;
 
   if (debug_lvl & 1) { // Standard console startup message output
     if (from == 0) { // Constructor
       cout << "      INPUT: " << InputNodes[0]->getName() << endl;
-      cout << "      C1: " << C1 << endl;
-      cout << "      C2: " << C2 << endl;
-      cout << "      C3: " << C3 << endl;
-      cout << "      C4: " << C4 << endl;
-      cout << "      C5: " << C5 << endl;
-      cout << "      C6: " << C6 << endl;
+        switch (FilterType) {
+        case eLag:
+          if (PropertySign[1] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[1] == 0L) cout << "      C[1]: " << C[1] << endl;
+          else cout << "      C[1] is the value of property: " << sgn << PropertyNode[1]->GetName() << endl;
+          break;
+        case eLeadLag:
+          if (PropertySign[1] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[1] == 0L) cout << "      C[1]: " << C[1] << endl;
+          else cout << "      C[1] is the value of property: " << sgn << PropertyNode[1]->GetName() << endl;
+          if (PropertySign[2] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[2] == 0L) cout << "      C[2]: " << C[2] << endl;
+          else cout << "      C[2] is the value of property: " << sgn << PropertyNode[2]->GetName() << endl;
+          if (PropertySign[3] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[3] == 0L) cout << "      C[3]: " << C[3] << endl;
+          else cout << "      C[3] is the value of property: " << sgn << PropertyNode[3]->GetName() << endl;
+          if (PropertySign[4] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[4] == 0L) cout << "      C[4]: " << C[4] << endl;
+          else cout << "      C[4] is the value of property: " << sgn << PropertyNode[4]->GetName() << endl;
+          break;
+        case eOrder2:
+          if (PropertySign[1] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[1] == 0L) cout << "      C[1]: " << C[1] << endl;
+          else cout << "      C[1] is the value of property: " << sgn << PropertyNode[1]->GetName() << endl;
+          if (PropertySign[2] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[2] == 0L) cout << "      C[2]: " << C[2] << endl;
+          else cout << "      C[2] is the value of property: " << sgn << PropertyNode[2]->GetName() << endl;
+          if (PropertySign[3] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[3] == 0L) cout << "      C[3]: " << C[3] << endl;
+          else cout << "      C[3] is the value of property: " << sgn << PropertyNode[3]->GetName() << endl;
+          if (PropertySign[4] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[4] == 0L) cout << "      C[4]: " << C[4] << endl;
+          else cout << "      C[4] is the value of property: " << sgn << PropertyNode[4]->GetName() << endl;
+          if (PropertySign[5] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[5] == 0L) cout << "      C[5]: " << C[5] << endl;
+          else cout << "      C[5] is the value of property: " << sgn << PropertyNode[5]->GetName() << endl;
+          if (PropertySign[6] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[6] == 0L) cout << "      C[6]: " << C[6] << endl;
+          else cout << "      C[6] is the value of property: " << sgn << PropertyNode[6]->GetName() << endl;
+          break;
+        case eWashout:
+          if (PropertySign[1] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[1] == 0L) cout << "      C[1]: " << C[1] << endl;
+          else cout << "      C[1] is the value of property: " << sgn << PropertyNode[1]->GetName() << endl;
+          break;
+        case eIntegrator:
+          if (PropertySign[1] < 0.0) sgn="-";
+          else sgn = "";
+          if (PropertyNode[1] == 0L) cout << "      C[1]: " << C[1] << endl;
+          else cout << "      C[1] is the value of property: " << sgn << PropertyNode[1]->GetName() << endl;
+          break;
+       } 
       if (IsOutput) cout << "      OUTPUT: " << OutputNode->getName() << endl;
     }
   }
index 483730b5d29120722849fc987fb8dd1c42a9ee0e..42b647997bdd96001e778330ddf4f709e420515d 100644 (file)
@@ -64,12 +64,12 @@ time domain. The general format for a filter specification is:
 @code
 <typename name="name">
   <input> property </input>
-  <c1> value </c1>
-  [<c2> value </c2>]
-  [<c3> value </c3>]
-  [<c4> value </c4>]
-  [<c5> value </c5>]
-  [<c6> value </c6>]
+  <c1> value|property </c1>
+  [<c2> value|property </c2>]
+  [<c3> value|property </c3>]
+  [<c4> value|property </c4>]
+  [<c5> value|property </c5>]
+  [<c6> value|property </c6>]
   [<clipto>
     <min> {[-]property name | value} </min>
     <max> {[-]property name | value} </max>
@@ -91,7 +91,7 @@ the corresponding filter definition is:
 @code
 <lag_filter name="name">
   <input> property </input>
-  <c1> value </c1>
+  <c1> value|property </c1>
   [<clipto>
     <min> {[-]property name | value} </min>
     <max> {[-]property name | value} </max>
@@ -130,10 +130,10 @@ The corresponding filter definition is:
 @code
 <lead_lag_filter name="name">
   <input> property </input>
-  <c1> value <c/1>
-  <c2> value <c/2>
-  <c3> value <c/3>
-  <c4> value <c/4>
+  <c1> value|property <c/1>
+  <c2> value|property <c/2>
+  <c3> value|property <c/3>
+  <c4> value|property <c/4>
   [<clipto>
     <min> {[-]property name | value} </min>
     <max> {[-]property name | value} </max>
@@ -177,12 +177,12 @@ The corresponding filter definition is:
 @code
 <second_order_filter name="name">
   <input> property </input>
-  <c1> value </c1>
-  <c2> value </c2>
-  <c3> value </c3>
-  <c4> value </c4>
-  <c5> value </c5>
-  <c6> value </c6>
+  <c1> value|property </c1>
+  <c2> value|property </c2>
+  <c3> value|property </c3>
+  <c4> value|property </c4>
+  <c5> value|property </c5>
+  <c6> value|property </c6>
   [<clipto>
     <min> {[-]property name | value} </min>
     <max> {[-]property name | value} </max>
@@ -204,7 +204,7 @@ The corresponding filter definition is:
 @code
 <integrator name="name">
   <input> property </input>
-  <c1> value </c1>
+  <c1> value|property </c1>
   [<trigger> property </trigger>]
   [<clipto>
     <min> {[-]property name | value} </min>
@@ -254,17 +254,17 @@ private:
   double cc;
   double cd;
   double ce;
-  double C1;
-  double C2;
-  double C3;
-  double C4;
-  double C5;
-  double C6;
+  double C[7]; // There are 6 coefficients, indexing is "1" based.
+  double PropertySign[7];
   double PreviousInput1;
   double PreviousInput2;
   double PreviousOutput1;
   double PreviousOutput2;
   FGPropertyManager* Trigger;
+  FGPropertyManager* PropertyNode[7];
+  void CalculateDynamicFilters(void);
+  void ReadFilterCoefficients(Element* el, int index);
+  bool DynamicFilter;
   void Debug(int from);
 };
 }
index 484074901635e37ff90e449659bf078c0df05014..d7eb22fc177ad308ca34433deed2584c246ee2cf 100644 (file)
@@ -54,6 +54,7 @@ FGGain::FGGain(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
   string strScheduledBy, gain_string, sZeroCentered;
 
   GainPropertyNode = 0;
+  GainPropertySign = 1.0;
   Gain = 1.000;
   Rows = 0;
   Table = 0;
@@ -69,8 +70,11 @@ FGGain::FGGain(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
 
   if ( element->FindElement("gain") ) {
     gain_string = element->FindElementValue("gain");
-    //ToDo allow for negative sign here for property
-    if (gain_string.find_first_not_of("+-.0123456789") != string::npos) { // property
+    if (gain_string.find_first_not_of("+-.0123456789Ee") != string::npos) { // property
+      if (gain_string[0] == '-') {
+       GainPropertySign = -1.0;
+       gain_string.erase(0,1);
+      }
       GainPropertyNode = PropertyManager->GetNode(gain_string);
     } else {
       Gain = element->FindElementValueAsNumber("gain");
@@ -126,6 +130,8 @@ FGGain::FGGain(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
 
 FGGain::~FGGain()
 {
+  delete Table;
+
   Debug(1);
 }
 
@@ -137,7 +143,7 @@ bool FGGain::Run(void )
 
   Input = InputNodes[0]->getDoubleValue() * InputSigns[0];
 
-  if (GainPropertyNode != 0) Gain = GainPropertyNode->getDoubleValue();
+  if (GainPropertyNode != 0) Gain = GainPropertyNode->getDoubleValue() * GainPropertySign;
 
   if (Type == "PURE_GAIN") {                       // PURE_GAIN
 
index e06382a99e17f22d56ced77a33298f71e02db3d7..d0f501e4ea71c1c8f7c04d4704f25b760fdeeba6 100644 (file)
@@ -234,6 +234,7 @@ public:
 private:
   FGTable* Table;
   FGPropertyManager* GainPropertyNode;
+  double GainPropertySign;
   double Gain;
   double InMin, InMax, OutMin, OutMax;
   int Rows;
index 94c1e7d74e2fc6b6709557f47d94115942052c7d..71eeedffb59ea9ee8c8e812fef3c280894024e81 100644 (file)
@@ -81,7 +81,7 @@ vehicle control or configuration. The form of the component specification is:
       <position> number </position>
       <time> number </time>
     </setting>
-    \85
+    ...
   </traverse>
   [<clipto>
     <min> {[-]property name | value} </min>
@@ -123,12 +123,8 @@ CLASS DECLARATION
 class FGKinemat  : public FGFCSComponent {
 public:
   /** Constructor.
-      @param fcs A reference to the ccurrent flightcontrolsystem.
-      @param AC_cfg reference to the current aircraft configuration file.
-      Initializes the FGKinemat object from the given configuration
-      file. The Configuration file is expected to be at the stream
-      position where the kinematic object starts. Also it is expected to
-      be past the end of the current kinematic configuration on exit.
+      @param fcs A reference to the current flight control system.
+      @param element reference to the current configuration file node.
    */
   FGKinemat(FGFCS* fcs, Element* element);
 
index 7917d1fedd74c6ad7e06f4c8417b87891f22ffb4..e2395e3a114fad6949ae7bf556452219738a9b3d 100755 (executable)
@@ -48,16 +48,62 @@ CLASS IMPLEMENTATION
 
 FGPID::FGPID(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
 {
+  string kp_string, ki_string, kd_string;
   dt = fcs->GetState()->Getdt();
 
   Kp = Ki = Kd = 0.0;
-  P_out = D_out = I_out = 0.0;
+  KpPropertyNode = 0;
+  KiPropertyNode = 0;
+  KdPropertyNode = 0;
+  KpPropertySign = 1.0;
+  KiPropertySign = 1.0;
+  KdPropertySign = 1.0;
+  I_out_total = 0.0;
   Input_prev = Input_prev2 = 0.0;
   Trigger = 0;
 
-  if (element->FindElement("kp")) Kp = element->FindElementValueAsNumber("kp");
-  if (element->FindElement("ki")) Ki = element->FindElementValueAsNumber("ki");
-  if (element->FindElement("kd")) Kd = element->FindElementValueAsNumber("kd");
+  if ( element->FindElement("kp") ) {
+    kp_string = element->FindElementValue("kp");
+    if (kp_string.find_first_not_of("+-.0123456789Ee") != string::npos) { // property
+      if (kp_string[0] == '-') {
+       KpPropertySign = -1.0;
+       kp_string.erase(0,1);
+      }
+      KpPropertyNode = PropertyManager->GetNode(kp_string);
+    } else {
+      Kp = element->FindElementValueAsNumber("kp");
+    }
+  }
+
+  if ( element->FindElement("ki") ) {
+    ki_string = element->FindElementValue("ki");
+    if (ki_string.find_first_not_of("+-.0123456789Ee") != string::npos) { // property
+      if (ki_string[0] == '-') {
+       KiPropertySign = -1.0;
+       ki_string.erase(0,1);
+      }
+      KiPropertyNode = PropertyManager->GetNode(ki_string);
+    } else {
+      Ki = element->FindElementValueAsNumber("ki");
+    }
+  }
+
+  if ( element->FindElement("kd") ) {
+    kd_string = element->FindElementValue("kd");
+    if (kd_string.find_first_not_of("+-.0123456789Ee") != string::npos) { // property
+      if (kd_string[0] == '-') {
+       KdPropertySign = -1.0;
+       kd_string.erase(0,1);
+      }
+      KdPropertyNode = PropertyManager->GetNode(kd_string);
+    } else {
+      Kd = element->FindElementValueAsNumber("kd");
+    }
+  }
+
+  //if (element->FindElement("kp")) Kp = element->FindElementValueAsNumber("kp");
+  //if (element->FindElement("ki")) Ki = element->FindElementValueAsNumber("ki");
+  //if (element->FindElement("kd")) Kd = element->FindElementValueAsNumber("kd");
   if (element->FindElement("trigger")) {
     Trigger =  PropertyManager->GetNode(element->FindElementValue("trigger"));
   }
@@ -78,29 +124,38 @@ FGPID::~FGPID()
 
 bool FGPID::Run(void )
 {
+  double I_out_delta = 0.0;
+  double P_out, D_out;
+
   Input = InputNodes[0]->getDoubleValue() * InputSigns[0];
 
-  P_out = Kp * (Input - Input_prev);
-  D_out = (Kd / dt) * (Input - 2*Input_prev + Input_prev2);
+  if (KpPropertyNode != 0) Kp = KpPropertyNode->getDoubleValue() * KpPropertySign;
+  if (KiPropertyNode != 0) Ki = KiPropertyNode->getDoubleValue() * KiPropertySign;
+  if (KdPropertyNode != 0) Kd = KdPropertyNode->getDoubleValue() * KdPropertySign;
+
+  P_out = Kp * Input;
+  D_out = (Kd / dt) * (Input - Input_prev);
 
   // Do not continue to integrate the input to the integrator if a wind-up
   // condition is sensed - that is, if the property pointed to by the trigger
-  // element is non-zero.
+  // element is non-zero. Reset the integrator to 0.0 if the Trigger value
+  // is negative.
 
   if (Trigger != 0) {
     double test = Trigger->getDoubleValue();
-    if (fabs(test) < 0.000001) {
-      I_out = Ki * dt * Input;
-    }
+    if (fabs(test) < 0.000001) I_out_delta = Ki * dt * Input;  // Normal
+    if (test < 0.0)            I_out_total = 0.0;  // Reset integrator to 0.0
   } else { // no anti-wind-up trigger defined
-    I_out = Ki * dt * Input;
+    I_out_delta = Ki * dt * Input;
   }
+  
+  I_out_total += I_out_delta;
 
+  Output = P_out + I_out_total + D_out;
+  
   Input_prev = Input;
   Input_prev2 = Input_prev;
 
-  Output += P_out + I_out + D_out;
-
   Clip();
   if (IsOutput) SetOutput();
 
index 7f69f2eb7ca131d6b44ae516ab093682d7f5c15c..b365f3537ddc57cfeaece31e5c7ccc5b95282935 100755 (executable)
@@ -69,6 +69,27 @@ CLASS DOCUMENTATION
 
 /** Encapsulates a PID control component for the flight control system.
 
+<h3>Configuration Format:</h3>
+
+@code
+<pid name="{string}">
+  <kp> {number} </kp>
+  <ki> {number} </ki>
+  <kd> {number} </kd>
+  <trigger> {string} </trigger>
+</pid>
+@endcode
+
+<h3>Configuration Parameters:</h3>
+<pre>
+
+  kp      - Proportional constant, default value 0.
+  ki      - Integrative constant, default value 0.
+  kd      - Derivative constant, default value 0.
+  trigger - Property which is used to sense wind-up, optional.
+
+</pre>
+
     @author Jon S. Berndt
     @version $Revision$
 */
@@ -89,8 +110,14 @@ private:
   double dt;
   FGPropertyManager *Trigger;
   double Kp, Ki, Kd;
-  double P_out, D_out, I_out;
+  double I_out_total;
   double Input_prev, Input_prev2;
+  double KpPropertySign;
+  double KiPropertySign;
+  double KdPropertySign;
+  FGPropertyManager* KpPropertyNode;
+  FGPropertyManager* KiPropertyNode;
+  FGPropertyManager* KdPropertyNode;
 
   void Debug(int from);
 };
index 72278f05901c3bd08b60da8521ef5184057281d0..19bf872af46af939348bbf505d6f6ce15259c499 100755 (executable)
@@ -144,6 +144,7 @@ bool FGSensor::Run(void )
   if (bits != 0)             Quantize();  // models quantization degradation
 //  if (delay != 0.0)          Delay();     // models system signal transport latencies
 
+  Clip(); // Is it right to clip a sensor?
   return true;
 }
 
index 4789996b7819374519446600aa7a3daf03b133a4..fddede8577e180ce547aaed5a06368c632dd9ca5 100755 (executable)
@@ -63,10 +63,10 @@ CLASS DOCUMENTATION
 Syntax:
 
 @code
-<sensor name=\94name\94>
+<sensor name="name">
   <input> property </input>
   <lag> number </lag>
-  <noise variation=\94PERCENT|ABSOLUTE\94> number </noise>
+  <noise variation="PERCENT|ABSOLUTE"> number </noise>
   <quantization name="name">
     <bits> number </bits>
     <min> number </min>
@@ -80,10 +80,10 @@ Syntax:
 Example:
 
 @code
-<sensor name=\94aero/sensor/qbar\94>
+<sensor name="aero/sensor/qbar">
   <input> aero/qbar </input>
   <lag> 0.5 </lag>
-  <noise variation=\94PERCENT\94> 2 </noise>
+  <noise variation="PERCENT"> 2 </noise>
   <quantization name="aero/sensor/quantized/qbar">
     <bits> 12 </bits>
     <min> 0 </min>
index 0503f04a820e104dd4de9d8719ff8384f925eff5..5071e7a2d1a440d87faf65af7940e84895858e3d 100644 (file)
@@ -119,8 +119,6 @@ void FGSummer::Debug(int from)
           cout << "       " << InputNodes[i]->getName() << endl;
       }
       if (Bias != 0.0) cout << "       Bias: " << Bias << endl;
-      if (clip) cout << "      CLIPTO: " << clipmin
-                                  << ", " << clipmax << endl;
       if (IsOutput) cout << "      OUTPUT: " <<OutputNode->getName() <<  endl;
     }
   }
index 8bf5fbbdfb78f2e611e8a1b88e22aafd21ae46d2..ed65eead94c0aa4eefca397e8138df67a7810b95 100644 (file)
@@ -72,28 +72,42 @@ CLASS DOCUMENTATION
     The Summer component sums two or more inputs. These can be pilot control
     inputs or state variables, and a bias can also be added in using the BIAS
     keyword.  The form of the summer component specification is:
-<pre>
-    \<COMPONENT NAME="name" TYPE="SUMMER">
-      INPUT \<property>
-      INPUT \<property>
-      [BIAS \<value>]
-      [?]
-      [CLIPTO \<min> \<max> 1]
-      [OUTPUT \<property>]
-    \</COMPONENT>
-</pre>
+@code
+    <summer name="{string}">
+      <input> {string} </input>
+      <input> {string} </input>
+      <bias> {number} </bias>
+      <clipto>
+         <min> {number} </min>
+         <max> {number} </max>
+      </clipto>
+      <output> {string} </output>
+    </summer>
+@endcode
+
     Note that in the case of an input property the property name may be
     immediately preceded by a minus sign. Here's an example of a summer
     component specification:
+
+@code
+    <summer name="Roll A/P Error summer">
+      <input> velocities/p-rad_sec </input>
+      <input> -fcs/roll-ap-wing-leveler </input>
+      <input> fcs/roll-ap-error-integrator </input>
+      <clipto>
+         <min> -1 </min>
+         <max>  1 </max> 
+      </clipto>
+    </summer>
+@endcode
+
 <pre>
-    \<COMPONENT NAME="Roll A/P Error summer" TYPE="SUMMER">
-      INPUT  velocities/p-rad_sec
-      INPUT -fcs/roll-ap-wing-leveler
-      INPUT  fcs/roll-ap-error-integrator
-      CLIPTO -1 1
-    \</COMPONENT>
+    Notes:
+
+    There can be only one BIAS statement per component.
+
+    There may be any number of inputs.
 </pre>
-    Note that there can be only one BIAS statement per component.
 
     @author Jon S. Berndt
     @version $Id$
@@ -108,7 +122,7 @@ class FGSummer  : public FGFCSComponent
 public:
   /** Constructor.
       @param fcs a pointer to the parent FGFCS object.
-      @param AC_cfg a pointer to the configuration file object. */
+      @param element a pointer to the configuration file node. */
   FGSummer(FGFCS* fcs, Element* element);
   /// Destructor
   ~FGSummer();
index 782cc0eec830dddd270f0cca1b740ad1345993ba..3bd3b661dbe834a09c506c129eaf1a0fccefab47 100644 (file)
@@ -78,15 +78,17 @@ FGSwitch::FGSwitch(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
   struct test *current_test;
   Element *test_element, *condition_element;
 
+  FGFCSComponent::bind(); // Bind() this component here in case it is used
+                          // in its own definition for a sample-and-hold
+
   test_element = element->GetElement();
   while (test_element) {
     if (test_element->GetName() == "default") {
-      tests.push_back(test());
-      current_test = &tests.back();
+      current_test = new struct test;
       current_test->Logic = eDefault;
+      tests.push_back(current_test);
     } else if (test_element->GetName() == "test") { // here's a test
-      tests.push_back(test());
-      current_test = &tests.back();
+      current_test = new struct test;
       logic = test_element->GetAttributeValue("logic");
       if (logic == "OR") current_test->Logic = eOR;
       else if (logic == "AND") current_test->Logic = eAND;
@@ -94,15 +96,17 @@ FGSwitch::FGSwitch(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
       else { // error
         cerr << "Unrecognized LOGIC token " << logic << " in switch component: " << Name << endl;
       }
-      for (unsigned int i=0; i<test_element->GetNumDataLines(); i++)
-        current_test->conditions.push_back(FGCondition(test_element->GetDataLine(i), PropertyManager));
+      for (unsigned int i=0; i<test_element->GetNumDataLines(); i++) {
+        current_test->conditions.push_back(new FGCondition(test_element->GetDataLine(i), PropertyManager));
+      }
 
       condition_element = test_element->GetElement(); // retrieve condition groups
       while (condition_element) {
-        current_test->conditions.push_back(FGCondition(condition_element, PropertyManager));
+        current_test->conditions.push_back(new FGCondition(condition_element, PropertyManager));
         condition_element = test_element->GetNextElement();
       }
 
+      tests.push_back(current_test);
     }
 
     if (test_element->GetName() != "output") { // this is not an output element
@@ -125,12 +129,9 @@ FGSwitch::FGSwitch(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
         }
       }
     }
-
     test_element = element->GetNextElement();
   }
 
-  FGFCSComponent::bind();
-
   Debug(0);
 }
 
@@ -138,6 +139,11 @@ FGSwitch::FGSwitch(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
 
 FGSwitch::~FGSwitch()
 {
+  for (unsigned int i=0; i<tests.size(); i++) {
+    for (unsigned int j=0; j<tests[i]->conditions.size(); j++) delete tests[i]->conditions[j];
+    delete tests[i];
+  }
+
   Debug(1);
 }
 
@@ -145,37 +151,33 @@ FGSwitch::~FGSwitch()
 
 bool FGSwitch::Run(void )
 {
-  vector <test>::iterator iTests = tests.begin();
-  vector <FGCondition>::iterator iConditions;
   bool pass = false;
+  double default_output=0.0;
 
-  while (iTests < tests.end()) {
-    iConditions = iTests->conditions.begin();
-
-    if (iTests->Logic == eDefault) {
-      Output = iTests->GetValue();
-    } else if (iTests->Logic == eAND) {
+  for (unsigned int i=0; i<tests.size(); i++) {
+    if (tests[i]->Logic == eDefault) {
+      default_output = tests[i]->GetValue();
+    } else if (tests[i]->Logic == eAND) {
       pass = true;
-      while (iConditions < iTests->conditions.end()) {
-        if (!iConditions->Evaluate()) pass = false;
-        *iConditions++;
+      for (unsigned int j=0; j<tests[i]->conditions.size(); j++) {
+        if (!tests[i]->conditions[j]->Evaluate()) pass = false;
       }
-    } else if (iTests->Logic == eOR) {
+    } else if (tests[i]->Logic == eOR) {
       pass = false;
-      while (iConditions < iTests->conditions.end()) {
-        if (iConditions->Evaluate()) pass = true;
-        *iConditions++;
+      for (unsigned int j=0; j<tests[i]->conditions.size(); j++) {
+        if (tests[i]->conditions[j]->Evaluate()) pass = true;
       }
     } else {
       cerr << "Invalid logic test" << endl;
     }
 
     if (pass) {
-      Output = iTests->GetValue();
+      Output = tests[i]->GetValue();
       break;
     }
-    *iTests++;
   }
+  
+  if (!pass) Output = default_output;
 
   Clip();
   if (IsOutput) SetOutput();
@@ -204,8 +206,6 @@ bool FGSwitch::Run(void )
 
 void FGSwitch::Debug(int from)
 {
-  vector <test>::iterator iTests = tests.begin();
-  vector <FGCondition>::iterator iConditions;
   string comp, scratch;
   string indent = "        ";
   bool first = false;
@@ -214,11 +214,11 @@ void FGSwitch::Debug(int from)
 
   if (debug_lvl & 1) { // Standard console startup message output
     if (from == 0) { // Constructor
-      while (iTests < tests.end()) {
+      for (unsigned int i=0; i<tests.size(); i++) {
 
         scratch = " if ";
 
-        switch(iTests->Logic) {
+        switch(tests[i]->Logic) {
         case (elUndef):
           comp = " UNSET ";
           cerr << "Unset logic for test condition" << endl;
@@ -237,26 +237,23 @@ void FGSwitch::Debug(int from)
           cerr << "Unknown logic for test condition" << endl;
         }
 
-        if (iTests->OutputProp != 0L)
-          if (iTests->sign < 0)
-            cout << indent << "Switch VALUE is - " << iTests->OutputProp->GetName() << scratch << endl;
+        if (tests[i]->OutputProp != 0L)
+          if (tests[i]->sign < 0)
+            cout << indent << "Switch VALUE is - " << tests[i]->OutputProp->GetName() << scratch << endl;
           else
-            cout << indent << "Switch VALUE is " << iTests->OutputProp->GetName() << scratch << endl;
+            cout << indent << "Switch VALUE is " << tests[i]->OutputProp->GetName() << scratch << endl;
         else
-          cout << indent << "Switch VALUE is " << iTests->OutputVal << scratch << endl;
+          cout << indent << "Switch VALUE is " << tests[i]->OutputVal << scratch << endl;
 
-        iConditions = iTests->conditions.begin();
         first = true;
-        while (iConditions < iTests->conditions.end()) {
+        for (unsigned int j=0; j<tests[i]->conditions.size(); j++) {
           if (!first) cout << indent << comp << " ";
           else cout << indent << " ";
           first = false;
-          iConditions->PrintCondition();
+          tests[i]->conditions[j]->PrintCondition();
           cout << endl;
-          *iConditions++;
         }
         cout << endl;
-        *iTests++;
       }
       if (IsOutput) cout << "      OUTPUT: " << OutputNode->getName() << endl;
     }
index cca569c0e303516237efdd5b03e173ce4fd9f586..ee379583e5b0fbbe9348f226fc51ee52ca2e5968 100644 (file)
@@ -122,6 +122,7 @@ output property of the component, addressed by the property, ap/roll-ap-autoswit
 is 0.0.  If or when the attitude hold switch is selected (property
 ap/attitude_hold takes the value 1), the value of the switch component will be
 whatever value fcs/roll-ap-error-summer is.
+
 @author Jon S. Berndt
 @version $Id$
 */
@@ -152,7 +153,7 @@ public:
 private:
 
   struct test {
-    vector <FGCondition> conditions;
+    vector <FGCondition*> conditions;
     eLogic Logic;
     double OutputVal;
     FGPropertyManager *OutputProp;
@@ -172,7 +173,7 @@ private:
 
   };
 
-  vector <test> tests;
+  vector <test*> tests;
 
   void Debug(int from);
 };
index 20e5692304f30c56896364fa81e25584ce9337ca..58e5bc2ce41e0cc73f7cb0ede0a998425f656e83 100644 (file)
@@ -57,11 +57,13 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Models and electric motor.
+/** Models an electric motor.
     FGElectric models an electric motor based on the configuration file
-    POWER_WATTS parameter.  The throttle controls motor output linearly from
-    zero to POWER_WATTS.  This power value (converted internally to horsepower)
-    is then used by FGPropeller to apply torque to the propeller.
+    \<power> parameter.  The throttle controls motor output linearly from
+    zero to \<power>.  This power value (converted internally to horsepower)
+    is then used by FGPropeller to apply torque to the propeller.  At present
+    there is no battery model available, so this motor does not consume any
+    energy.  There is no internal friction.
     @author David Culp
     @version "$Id$"
   */
index b40cdb3490a0d36e8cfe6e9980c6fe387dd6d713..08c2e5be6748bf33980c6b8c5253ed738fcdada8 100644 (file)
@@ -81,17 +81,8 @@ FGEngine::FGEngine(FGFDMExec* exec, Element* engine_element, int engine_number)
   SLFuelFlowMax = SLOxiFlowMax = 0.0;
   MaxThrottle = 1.0;
   MinThrottle = 0.0;
-  Thrust = 0.0;
-  Throttle = 0.0;
-  Mixture = 1.0;
-  Starter = false;
-  FuelNeed = OxidizerNeed = 0.0;
-  Starved = Running = Cranking = false;
-  PctPower = 0.0;
-  TrimMode = false;
-  FuelFlow_gph = 0.0;
-  FuelFlow_pph = 0.0;
-  FuelFreeze = false;
+
+  ResetToIC(); // initialize dynamic terms
 
   FDMExec = exec;
   State = FDMExec->GetState();
@@ -113,15 +104,16 @@ FGEngine::FGEngine(FGFDMExec* exec, Element* engine_element, int engine_number)
   else      cerr << "No engine location found for this engine." << endl;
 
   local_element = engine_element->GetParent()->FindElement("orient");
-  if (local_element)  orientation = local_element->FindElementTripletConvertTo("DEG");
-  else          cerr << "No engine orientation found for this engine." << endl;
+  if (local_element)  orientation = local_element->FindElementTripletConvertTo("RAD");
+//  else          cerr << "No engine orientation found for this engine." << endl;
+// Jon: The engine orientation has a default and is not normally used.
 
   SetPlacement(location, orientation);
 
   // Load thruster
   local_element = engine_element->GetParent()->FindElement("thruster");
   if (local_element) {
-    LoadThruster(local_element);
+    if (!LoadThruster(local_element)) exit(-1);
   } else {
     cerr << "No thruster definition supplied with engine definition." << endl;
   }
@@ -137,6 +129,11 @@ FGEngine::FGEngine(FGFDMExec* exec, Element* engine_element, int engine_number)
     cerr << "No feed tank specified in engine definition." << endl;
   }
 
+  char property_name[80];
+  snprintf(property_name, 80, "propulsion/engine[%d]/set-running", EngineNumber);
+  PropertyManager->Tie( property_name, (FGEngine*)this, &FGEngine::GetRunning,
+                                       &FGEngine::SetRunning );
+
   Debug(0);
 }
 
@@ -148,6 +145,23 @@ FGEngine::~FGEngine()
   Debug(1);
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGEngine::ResetToIC(void)
+{
+  Thrust = 0.0;
+  Throttle = 0.0;
+  Mixture = 1.0;
+  Starter = false;
+  FuelNeed = OxidizerNeed = 0.0;
+  Starved = Running = Cranking = false;
+  PctPower = 0.0;
+  TrimMode = false;
+  FuelFlow_gph = 0.0;
+  FuelFlow_pph = 0.0;
+  FuelFreeze = false;
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 // This base class function should be called from within the
 // derived class' Calculate() function before any other calculations are done.
index f60db357d163eaba546442e4bc4c8727045f3106..1f245683734f634b3f6bbd73a34483f5586fb65a 100644 (file)
@@ -94,7 +94,45 @@ CLASS DOCUMENTATION
 
 /** Base class for all engines.
     This base class contains methods and members common to all engines, such as
-    logic to drain fuel from the appropriate tank, etc.
+    logic to drain fuel from the appropriate tank, etc. 
+    <br>
+    <h3>Configuration File Format:</h3>
+@code
+        <engine file="{string}">
+            <location unit="{IN | M}">
+                <x> {number} </x>
+                <y> {number} </y>
+                <z> {number} </z>
+            </location>
+            <!-- optional orientation definition -->
+            <orient unit="{RAD | DEG}">
+                <roll>  {number} </roll>
+                <pitch> {number} </pitch>
+                <yaw> {number} </yaw>
+            </orient>
+            <feed> {integer} </feed>
+            ... optional more feed tank index numbers ... 
+            <thruster file="{string}">
+                <location unit="{IN | M}">
+                    <x> {number} </x>
+                    <y> {number} </y>
+                    <z> {number} </z>
+                </location>
+                <orient unit="{RAD | DEG}">
+                    <roll> {number} </roll>
+                    <pitch> {number} </pitch>
+                    <yaw> {number} </yaw>
+                </orient>
+            </thruster>
+        </engine>
+@endcode
+<pre>
+    NOTES:
+       Engines feed from all tanks equally.
+
+       Not all thruster types can be matched with a given engine type.  See the class
+       documentation for engine and thruster classes.
+</pre>     
     @author Jon S. Berndt
     @version $Id$
 */
@@ -125,7 +163,7 @@ public:
   virtual double getFuelFlow_pph () const {return FuelFlow_pph;}
   virtual double GetThrust(void) { return Thrust; }
   virtual bool   GetStarved(void) { return Starved; }
-  virtual bool   GetRunning(void) { return Running; }
+  virtual bool   GetRunning(void) const { return Running; }
   virtual bool   GetCranking(void) { return Cranking; }
 
   virtual void SetStarved(bool tt) { Starved = tt; }
@@ -138,6 +176,11 @@ public:
 
   virtual void SetStarter(bool s) { Starter = s; }
 
+  virtual int InitRunning(void){ return 1; }
+
+  /** Resets the Engine parameters to the initial conditions */
+  void ResetToIC(void);
+
   /** Calculates the thrust of the engine, and other engine functions.
       @return Thrust in pounds */
   virtual double Calculate(void) {return 0.0;}
index fec3686d9bd8db7f44dba2515661b69218c01eae..9f39088d7788d5702fadb42a32d71e1c1f2487b8 100644 (file)
@@ -40,12 +40,12 @@ and the cg.
 
 */
 
+#include "FGForce.h"
 #include <FGFDMExec.h>
 #include <models/FGAircraft.h>
 #include <models/FGPropagate.h>
 #include <models/FGMassBalance.h>
-#include <FGState.h>
-#include "FGForce.h"
+#include <models/FGAerodynamics.h>
 
 namespace JSBSim {
 
@@ -95,7 +95,7 @@ FGMatrix33 FGForce::Transform(void)
 {
   switch(ttype) {
   case tWindBody:
-    return fdmex->GetState()->GetTs2b();
+    return fdmex->GetAerodynamics()->GetTw2b();
   case tLocalBody:
     return fdmex->GetPropagate()->GetTl2b();
   case tCustom:
index ce62f239b5ff12fff59da21e54bb00ff5abe2424..0798d00e27c16184097449b2f6ef7151c318c72a 100644 (file)
@@ -195,7 +195,7 @@ other hand, will require it to be be called only once.</p>
 
 <p>Retrieval of the computed forces and moments is done as detailed above.</p>
 <br>
-<blockquote>
+<pre>
     <p><i>CAVEAT: If the custom system is used to compute
     the wind-to-body transform, then the sign of the sideslip
     angle must be reversed when calling SetAnglesToBody().
@@ -203,8 +203,8 @@ other hand, will require it to be be called only once.</p>
     hand rule. Using the custom transform type this way
     should not be necessary, as it is already provided as a built
     in type (and the sign differences are correctly accounted for).</i>
-    <br></p>
-</blockquote>
+    </p>
+</pre>
 
 <h4>Use as a Base Type</h4>
 
@@ -227,12 +227,18 @@ class FGForce : public FGJSBBase
 public:
   /// Constructor
   FGForce(FGFDMExec *FDMExec);
+  FGForce(const FGForce& force) {
+    vFn = force.vFn;
+    vXYZn = force.vXYZn;
+    ttype = force.ttype;
+    fdmex = force.fdmex;
+  }
   /// Destructor
   ~FGForce();
 
   enum TransformType { tNone, tWindBody, tLocalBody, tCustom };
 
-  FGColumnVector3& GetBodyForces(void);
+  virtual FGColumnVector3& GetBodyForces(void);
 
   inline FGColumnVector3& GetMoments(void) { return vM; }
 
index f2aaf358a84cf684814e92ff78978b57565f3306..dfa3ffd7d045a4b2c438d63485bc3225149c429c 100644 (file)
@@ -56,7 +56,28 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Models a rocket nozzle.
+/** Models a rocket nozzle. 
+
+<h3>Configuration File Format:</h3>
+
+@code
+<nozzle name="{string}">
+  <pe unit="{PSF}"> {number}  </pe>
+  <expr>  {number}  </expr>
+  <nzl_eff>  {number}  </nzl_eff>
+  <diam unit="{FT | M | IN}"> {number}  </diam>
+</nozzle>
+@endcode
+
+<h3>Configuration parameters are:</h3>
+<pre>
+    <b>pe</b> -      Nozzle exit pressure.
+    <b>expr</b> -    Nozzle expansion ratio, Ae/At, sqft. dimensionless ratio.
+    <b>nzl_eff</b> - Nozzle efficiency, 0.0 - 1.0.
+    <b>diam</b> -    Nozzle diameter.
+</pre>
+
+    All parameters MUST be specified.  
     @author Jon S. Berndt
     @version $Id$
 */
index 3526b6d7d8c163597a0fe7dcfa769e96d52bc43c..bf9375f49716945deba2d4f2c7a2e0217464e51b 100644 (file)
@@ -67,12 +67,14 @@ FGPiston::FGPiston(FGFDMExec* exec, Element* el, int engine_number)
   // Defaults and initializations
 
   Type = etPiston;
+  dt = State->Getdt();
 
   // These items are read from the configuration file
 
   Cycles = 2;
   IdleRPM = 600;
   Displacement = 360;
+  SparkFailDrop = 1.0;
   MaxHP = 200;
   MinManifoldPressure_inHg = 6.5;
   MaxManifoldPressure_inHg = 28.5;
@@ -80,17 +82,11 @@ FGPiston::FGPiston(FGFDMExec* exec, Element* el, int engine_number)
   // These are internal program variables
 
   crank_counter = 0;
-  OilTemp_degK = RankineToKelvin(Atmosphere->GetTemperature());
-  ManifoldPressure_inHg = Atmosphere->GetPressure() * psftoinhg; // psf to in Hg
+  Magnetos = 0;
   minMAP = 21950;
   maxMAP = 96250;
-  MAP = Atmosphere->GetPressure() * psftopa;
-  CylinderHeadTemp_degK = RankineToKelvin(Atmosphere->GetTemperature());
-  Magnetos = 0;
-  ExhaustGasTemp_degK = RankineToKelvin(Atmosphere->GetTemperature());
-  EGT_degC = ExhaustGasTemp_degK - 273;
 
-  dt = State->Getdt();
+  ResetToIC();
 
   // Supercharging
   BoostSpeeds = 0;  // Default to no supercharging
@@ -157,6 +153,8 @@ FGPiston::FGPiston(FGFDMExec* exec, Element* el, int engine_number)
     Displacement = el->FindElementValueAsNumberConvertTo("displacement","IN3");
   if (el->FindElement("maxhp"))
     MaxHP = el->FindElementValueAsNumberConvertTo("maxhp","HP");
+  if (el->FindElement("sparkfaildrop"))
+    SparkFailDrop = Constrain(0, 1 - el->FindElementValueAsNumber("sparkfaildrop"), 1);
   if (el->FindElement("cycles"))
     Cycles = el->FindElementValueAsNumber("cycles");
   if (el->FindElement("idlerpm"))
@@ -196,8 +194,8 @@ FGPiston::FGPiston(FGFDMExec* exec, Element* el, int engine_number)
     if (el->FindElement("ratedaltitude3"))
       RatedAltitude[2] = el->FindElementValueAsNumberConvertTo("ratedaltitude3", "FT");
   }
-  minMAP = MinManifoldPressure_inHg * 3386.38;  // inHg to Pa
-  maxMAP = MaxManifoldPressure_inHg * 3386.38;
+  minMAP = MinManifoldPressure_inHg * inhgtopa;  // inHg to Pa
+  maxMAP = MaxManifoldPressure_inHg * inhgtopa;
   StarterHP = sqrt(MaxHP) * 0.4;
 
   // Set up and sanity-check the turbo/supercharging configuration based on the input values.
@@ -254,11 +252,30 @@ FGPiston::FGPiston(FGFDMExec* exec, Element* el, int engine_number)
 
 FGPiston::~FGPiston()
 {
+  delete Lookup_Combustion_Efficiency;
+  delete Power_Mixture_Correlation;
   Debug(1); // Call Debug() routine from constructor if needed
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGPiston::ResetToIC(void)
+{
+  FGEngine::ResetToIC();
+  
+  ManifoldPressure_inHg = Atmosphere->GetPressure() * psftoinhg; // psf to in Hg
+  MAP = Atmosphere->GetPressure() * psftopa;
+  double airTemperature_degK = RankineToKelvin(Atmosphere->GetTemperature());
+  OilTemp_degK = airTemperature_degK;
+  CylinderHeadTemp_degK = airTemperature_degK;
+  ExhaustGasTemp_degK = airTemperature_degK;
+  EGT_degC = ExhaustGasTemp_degK - 273;
+  Thruster->SetRPM(0.0);
+  RPM = 0.0;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 double FGPiston::Calculate(void)
 {
   if (FuelFlow_gph > 0.0) ConsumeFuel();
@@ -307,6 +324,23 @@ double FGPiston::Calculate(void)
   return Thruster->Calculate(PowerAvailable);
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+double FGPiston::CalcFuelNeed(void)
+{
+  return FuelFlow_gph / 3600 * 6 * State->Getdt() * Propulsion->GetRate();
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+int FGPiston::InitRunning(void) {
+  Magnetos=3;
+  //Thruster->SetRPM( 1.1*IdleRPM/Thruster->GetGearRatio() );
+  Thruster->SetRPM( 1000 );
+  Running=true;
+  return 1;
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 /**
  * Start or stop the engine.
@@ -469,7 +503,7 @@ void FGPiston::doMAP(void)
   }
 
   // And set the value in American units as well
-  ManifoldPressure_inHg = MAP / 3386.38;
+  ManifoldPressure_inHg = MAP / inhgtopa;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -567,6 +601,9 @@ void FGPiston::doEnginePower(void)
 
     Percentage_Power *= Percentage_of_best_power_mixture_power / 100.0;
 
+    if( Magnetos != 3 )
+      Percentage_Power *= SparkFailDrop;
+
     if (Boosted) {
       HP = Percentage_Power * RatedPower[BoostSpeed] / 100.0;
     } else {
@@ -819,11 +856,4 @@ void FGPiston::Debug(int from)
     }
   }
 }
-
-double
-FGPiston::CalcFuelNeed(void)
-{
-  return FuelFlow_gph / 3600 * 6 * State->Getdt() * Propulsion->GetRate();
-}
-
 } // namespace JSBSim
index cb4e503ba76275893c2f4840906fc3c0c94c381c..554ece8293d25b6a04ff6792b1c027cf92d310a5 100644 (file)
@@ -61,6 +61,38 @@ CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 /** Models Dave Luff's Turbo/Supercharged Piston engine model.
+
+<h3>Configuration File Format:</h3>
+
+@code
+<piston_engine name="{string}">
+  <minmp unit="{INHG | PA | ATM}"> {number} </minmp>
+  <maxmp unit="{INHG | PA | ATM}"> {number} </maxmp>
+  <displacement unit="{IN3 | LTR | CC}"> {number} </displacement>
+  <maxhp unit="{HP | WATTS}"> {number} </maxhp>
+  <cycles> {number} </cycles>
+  <idlerpm> {number} </idlerpm>
+  <maxthrottle> {number} </maxthrottle>
+  <minthrottle> {number} </minthrottle>
+  <numboostspeeds> {number} </numboostspeeds>
+  <boostoverride> {0 | 1} </boostoverride>
+  <ratedboost1 unit="{INHG | PA | ATM}"> {number} </ratedboost1>
+  <ratedpower1 unit="{HP | WATTS}"> {number} </ratedpower1>
+  <ratedrpm1> {number} </ratedrpm1>
+  <ratedaltitude1 unit="{FT | M}"> {number} </ratedaltitude1>
+  <ratedboost2 unit="{INHG | PA | ATM}"> {number} </ratedboost2>
+  <ratedpower2 unit="{HP | WATTS}"> {number} </ratedpower2>
+  <ratedrpm2> {number} </ratedrpm2>
+  <ratedaltitude2 unit="{FT | M}"> {number} </ratedaltitude2>
+  <ratedboost3 unit="{INHG | PA | ATM}"> {number} </ratedboost3>
+  <ratedpower3 unit="{HP | WATTS}"> {number} </ratedpower3>
+  <ratedrpm3> {number} </ratedrpm3>
+  <ratedaltitude3 unit="{FT | M}"> {number} </ratedaltitude3>
+  <takeoffboost unit="{INHG | PA | ATM}"> {number} </takeoffboost>
+</piston_engine>
+@endcode
+
+<pre>
     Additional elements are required for a supercharged engine.  These can be
     left off a non-supercharged engine, ie. the changes are all backward
     compatible at present.
@@ -127,6 +159,7 @@ CLASS DOCUMENTATION
     Note that MAXMP is still the non-boosted max manifold pressure even for
     boosted engines - effectively this is simply a measure of the pressure drop
     through the fully open throttle.
+</pre>
 
     @author Jon S. Berndt (Engine framework code and framework-related mods)
     @author Dave Luff (engine operational code)
@@ -153,6 +186,7 @@ public:
   double GetPowerAvailable(void) {return PowerAvailable;}
   double CalcFuelNeed(void);
 
+  void ResetToIC(void);
   void SetMagnetos(int magnetos) {Magnetos = magnetos;}
 
   double  GetEGT(void) { return EGT_degC; }
@@ -188,6 +222,8 @@ private:
   void doOilPressure(void);
   void doOilTemperature(void);
 
+  int InitRunning(void);
+
   //
   // constants
   //
@@ -208,6 +244,7 @@ private:
   double MaxManifoldPressure_inHg; // Inches Hg
   double Displacement;             // cubic inches
   double MaxHP;                    // horsepower
+  double SparkFailDrop;            // drop of power due to spark failure
   double Cycles;                   // cycles/power stroke
   double IdleRPM;                  // revolutions per minute
   double StarterHP;                // initial horsepower of starter motor 
index ca3289db511db738dcec65a7ab0b38cd4ca19070..55ea67ffe1f1726abc3dbe3ae5d94f30b1ab95cc 100644 (file)
@@ -71,6 +71,7 @@ FGPropeller::FGPropeller(FGFDMExec* exec, Element* prop_element, int num)
   Feathered = false;
   Reverse_coef = 0.0;
   GearRatio = 1.0;
+  CtFactor = CpFactor = 1.0;
 
   if (prop_element->FindElement("ixx"))
     Ixx = prop_element->FindElementValueAsNumberConvertTo("ixx", "SLUG*FT2");
@@ -114,6 +115,10 @@ FGPropeller::FGPropeller(FGFDMExec* exec, Element* prop_element, int num)
   if (P_Factor < 0) {
     cerr << "P-Factor value in config file must be greater than zero" << endl;
   }
+  if (prop_element->FindElement("ct_factor"))
+    SetCtFactor( prop_element->FindElementValueAsNumber("ct_factor") );
+  if (prop_element->FindElement("cp_factor"))
+    SetCpFactor( prop_element->FindElementValueAsNumber("cp_factor") );
 
   Type = ttPropeller;
   RPM = 0;
@@ -128,6 +133,8 @@ FGPropeller::FGPropeller(FGFDMExec* exec, Element* prop_element, int num)
   PropertyManager->Tie( property_name, &Pitch );
   snprintf(property_name, 80, "propulsion/engine[%d]/thrust-coefficient", EngineNum);
   PropertyManager->Tie( property_name, this, &FGPropeller::GetThrustCoefficient );
+  snprintf(property_name, 80, "propulsion/engine[%d]/propeller-rpm", EngineNum);
+  PropertyManager->Tie( property_name, this, &FGPropeller::GetRPM );
 
   Debug(0);
 }
@@ -139,14 +146,6 @@ FGPropeller::~FGPropeller()
   delete cThrust;
   delete cPower;
 
-  char property_name[80];
-  snprintf(property_name, 80, "propulsion/engine[%d]/advance-ratio", EngineNum);
-  PropertyManager->Untie( property_name );
-  snprintf(property_name, 80, "propulsion/engine[%d]/blade-angle", EngineNum);
-  PropertyManager->Untie( property_name );
-  snprintf(property_name, 80, "propulsion/engine[%d]/thrust-coefficient", EngineNum);
-  PropertyManager->Untie( property_name );
-
   Debug(1);
 }
 
@@ -177,6 +176,7 @@ double FGPropeller::Calculate(double PowerAvailable)
 
   if (MaxPitch == MinPitch)  ThrustCoeff = cThrust->GetValue(J);
   else                       ThrustCoeff = cThrust->GetValue(J, Pitch);
+  ThrustCoeff *= CtFactor;
 
   if (P_Factor > 0.0001) {
     alpha = fdmex->GetAuxiliary()->Getalpha();
@@ -266,6 +266,7 @@ double FGPropeller::GetPowerRequired(void)
     }
     cPReq = cPower->GetValue(J, Pitch);
   }
+  cPReq *= CpFactor;
 
   if (RPS > 0) {
     PowerRequired = cPReq*RPS*RPS*RPS*D5*rho;
index 3da9e2546c0788e2a3c0e16d0a242fc1deb8fda3..65b344e53aa959e06cdff46252b1745ddbadf4b3 100644 (file)
@@ -57,13 +57,63 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Propeller modeling class.
-    FGPropeller models a propeller given the tabular data for Ct and Cp
-    indexed by advance ratio "J". The data for the propeller is
-    stored in a config file named "prop_name.xml". The propeller config file
-    is referenced from the main aircraft config file in the "Propulsion" section.
-    See the constructor for FGPropeller to see what is read in and what should
-    be stored in the config file.<br>
+/** FGPropeller models a propeller given the tabular data for Ct and Cp,
+    indexed by the advance ratio "J". 
+
+<h3>Configuration File Format:</h3>
+@code
+<propeller name="{string}">
+  <ixx> {number} </ixx>
+  <diameter unit="IN"> {number} </diameter>
+  <numblades> {number} </numblades>
+  <gearratio> {number} </gearratio>
+  <minpitch> {number} </minpitch>
+  <maxpitch> {number} </maxpitch>
+  <minrpm> {number} </minrpm>
+  <maxrpm> {number} </maxrpm>
+  <reversepitch> {number} </reversepitch>
+  <sense> {1 | -1} </sense>
+  <p_factor> {number} </p_factor>
+  <ct_factor> {number} </ct_factor>
+  <cp_factor> {number} </cp_factor>
+
+  <table name="C_THRUST" type="internal">
+    <tableData>
+      {numbers}
+    </tableData>
+  </table>
+
+  <table name="C_POWER" type="internal">
+    <tableData>
+      {numbers}
+    </tableData>
+  </table>
+
+</propeller>
+@endcode
+
+<h3>Configuration Parameters:</h3>
+<pre>
+    \<ixx>           - Propeller rotational inertia.
+    \<diameter>      - Propeller disk diameter.
+    \<numblades>     - Number of blades.
+    \<gearratio>     - Ratio of (engine rpm) / (prop rpm).
+    \<minpitch>      - Minimum blade pitch angle.
+    \<maxpitch>      - Maximum blade pitch angle.
+    \<minrpm>        - Minimum rpm target for constant speed propeller.
+    \<maxrpm>        - Maximum rpm target for constant speed propeller.
+    \<reversepitch>  - Blade pitch angle for reverse.
+    \<sense>         - Direction of rotation (1=clockwise as viewed from cockpit,
+                        -1=anti-clockwise as viewed from cockpit).
+    \<p_factor>      - P factor.
+    \<ct_factor>     - A multiplier for the coefficients of thrust.
+    \<cp_factor>     - A multiplier for the coefficients of power.
+</pre>
+
+    Two tables are needed. One for coefficient of thrust (Ct) and one for
+    coefficient of power (Cp).  
+    <br>
+
     Several references were helpful, here:<ul>
     <li>Barnes W. McCormick, "Aerodynamics, Aeronautics, and Flight Mechanics",
      Wiley & Sons, 1979 ISBN 0-471-03032-5</li>
@@ -87,7 +137,8 @@ class FGPropeller : public FGThruster {
 public:
   /** Constructor for FGPropeller.
       @param exec a pointer to the main executive object
-      @param el a pointer to the thruster config file XML element*/
+      @param el a pointer to the thruster config file XML element
+      @param num the number of this propeller */
   FGPropeller(FGFDMExec* exec, Element* el, int num = 0);
 
   /// Destructor for FGPropeller - deletes the FGTable objects
@@ -118,6 +169,12 @@ public:
   /// Sets the P-Factor constant
   void SetPFactor(double pf) {P_Factor = pf;}
 
+  /// Sets coefficient of thrust multiplier
+  void SetCtFactor(double ctf) {CtFactor = ctf;}
+
+  /// Sets coefficient of power multiplier
+  void SetCpFactor(double cpf) {CpFactor = cpf;}
+
   /** Sets the rotation sense of the propeller.
       @param s this value should be +/- 1 ONLY. +1 indicates clockwise rotation as
                viewed by someone standing behind the engine looking forward into
@@ -128,11 +185,25 @@ public:
   double GetPitch(void)         { return Pitch;         }
 
   /// Retrieves the RPMs of the propeller
-  double GetRPM(void)           { return RPM;           }
+  double GetRPM(void)     const { return RPM;           } 
 
   /// Retrieves the propeller moment of inertia
   double GetIxx(void)           { return Ixx;           }
 
+  /// Retrieves the coefficient of thrust multiplier
+  double GetCtFactor(void)      { return CtFactor;      }
+
+  /// Retrieves the coefficient of power multiplier
+  double GetCpFactor(void)      { return CpFactor;      }
+
+  /// Retrieves the propeller diameter
+  double GetDiameter(void)      { return Diameter;      }
+
+  /// Retrieves propeller thrust table
+  FGTable* GetCThrustTable(void) const { return cThrust;}
+  /// Retrieves propeller power table
+  FGTable* GetCPowerTable(void)  const { return cPower; }
+
   /// Retrieves the Torque in foot-pounds (Don't you love the English system?)
   double GetTorque(void)        { return vTorque(eX);    }
 
@@ -183,6 +254,8 @@ private:
   FGColumnVector3 vTorque;
   FGTable *cThrust;
   FGTable *cPower;
+  double CtFactor;
+  double CpFactor;
   void Debug(int from);
   double ReversePitch; // Pitch, when fully reversed
   bool   Reversed;              // true, when propeller is reversed
index 42436cc335bc32714c1ad65959884e14281c3d6d..3e44794065f598ea8668bd7e355e9eeeae120849 100644 (file)
@@ -90,8 +90,8 @@ CLASS DOCUMENTATION
     normalized thrust value looks roughly like this:
 
 <pre>    
 <thrust_table name="propulsion/thrust_time" type="internal">
-    <tableData>
\<thrust_table name="propulsion/thrust_time" type="internal">
+   \<tableData>
       0.0   0.00
       0.2   0.91
       8.0   0.97
@@ -114,8 +114,8 @@ CLASS DOCUMENTATION
     112.0   0.46
     120.0   0.09
     132.0   0.00
-    </tableData>
 </thrust_table>
+   \</tableData>
\</thrust_table>
 </pre>
 
 The left column is time, the right column is normalized thrust. Inside the
index 29c5e528411b4731434120c3e28bd1280007e56e..7f6d411b1e73def508e345db98f1ee04bb80c288 100644 (file)
@@ -36,8 +36,6 @@ HISTORY
 INCLUDES
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-#include <FGFDMExec.h>
-#include <models/FGAuxiliary.h>
 #include "FGTank.h"
 
 #if !defined ( sgi ) || defined( __GNUC__ ) && (_COMPILER_VERSION < 740)
@@ -55,14 +53,18 @@ static const char *IdHdr = ID_TANK;
 CLASS IMPLEMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-FGTank::FGTank(FGFDMExec* exec, Element* el)
+FGTank::FGTank(FGFDMExec* exec, Element* el, int tank_number)
+                  : TankNumber(tank_number)
 {
   string token;
   Element* element;
   Area = 1.0;
   Temperature = -9999.0;
   Auxiliary = exec->GetAuxiliary();
-  Radius = Capacity = Contents = 0.0;
+  Radius = Capacity = Contents = Standpipe = 0.0;
+  PropertyManager = exec->GetPropertyManager();
+  vXYZ.InitMatrix();
+  vXYZ_drain.InitMatrix();
 
   type = el->GetAttributeValue("type");
   if      (type == "FUEL")     Type = ttFUEL;
@@ -73,14 +75,23 @@ FGTank::FGTank(FGFDMExec* exec, Element* el)
   if (element)  vXYZ = element->FindElementTripletConvertTo("IN");
   else          cerr << "No location found for this tank." << endl;
 
+  vXYZ_drain = vXYZ; // Set initial drain location to initial tank CG
+
+  element = el->FindElement("drain_location");
+  if (element)  {
+    vXYZ_drain = element->FindElementTripletConvertTo("IN");
+  }
+
   if (el->FindElement("radius"))
     Radius = el->FindElementValueAsNumberConvertTo("radius", "IN");
   if (el->FindElement("capacity"))
     Capacity = el->FindElementValueAsNumberConvertTo("capacity", "LBS");
   if (el->FindElement("contents"))
-    Contents = el->FindElementValueAsNumberConvertTo("contents", "LBS");
+    InitialContents = Contents = el->FindElementValueAsNumberConvertTo("contents", "LBS");
   if (el->FindElement("temperature"))
-    Temperature = el->FindElementValueAsNumber("temperature");
+    InitialTemperature = Temperature = el->FindElementValueAsNumber("temperature");
+  if (el->FindElement("standpipe"))
+    InitialStandpipe = Standpipe = el->FindElementValueAsNumberConvertTo("standpipe", "LBS");
 
   Selected = true;
 
@@ -91,7 +102,12 @@ FGTank::FGTank(FGFDMExec* exec, Element* el)
     PctFull  = 0;
   }
 
-  if (Temperature != -9999.0)  Temperature = FahrenheitToCelsius(Temperature);
+  char property_name[80];
+  snprintf(property_name, 80, "propulsion/tank[%d]/contents-lbs", TankNumber);
+  PropertyManager->Tie( property_name, (FGTank*)this, &FGTank::GetContents,
+                                       &FGTank::SetContents );
+
+  if (Temperature != -9999.0)  InitialTemperature = Temperature = FahrenheitToCelsius(Temperature);
   Area = 40.0 * pow(Capacity/1975, 0.666666667);
 
   Debug(0);
@@ -106,19 +122,47 @@ FGTank::~FGTank()
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
+void FGTank::ResetToIC(void)
+{
+  Temperature = InitialTemperature;
+  Standpipe = InitialStandpipe;
+  Contents = InitialContents;
+  PctFull = 100.0*Contents/Capacity;
+  Selected = true;
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+const FGColumnVector3 FGTank::GetXYZ(void)
+{
+  return vXYZ_drain + (Contents/Capacity)*(vXYZ - vXYZ_drain);
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+const double FGTank::GetXYZ(int idx)
+{
+  return vXYZ_drain(idx) + (Contents/Capacity)*(vXYZ(idx)-vXYZ_drain(idx));
+}
+
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
 double FGTank::Drain(double used)
 {
-  double shortage = Contents - used;
+  double remaining = Contents - used;
+
+  if (remaining >= 0) { // Reduce contents by amount used.
 
-  if (shortage >= 0) {
     Contents -= used;
     PctFull = 100.0*Contents/Capacity;
-  } else {
+
+  } else { // This tank must be empty.
+
     Contents = 0.0;
     PctFull = 0.0;
     Selected = false;
   }
-  return shortage;
+  return remaining;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -161,11 +205,11 @@ double FGTank::Calculate(double dt)
   double TempFlowFactor = 1.115;      // Watts/sqft/C
   double TAT = Auxiliary->GetTAT_C();
   double Tdiff = TAT - Temperature;
-  double dT = 0.0;                    // Temp change due to one surface
+  double dTemp = 0.0;                 // Temp change due to one surface
   if (fabs(Tdiff) > 0.1) {
-    dT = (TempFlowFactor * Area * Tdiff * dt) / (Contents * HeatCapacity);
+    dTemp = (TempFlowFactor * Area * Tdiff * dt) / (Contents * HeatCapacity);
   }
-  return Temperature += (dT + dT);    // For now, assume upper/lower the same
+  return Temperature += (dTemp + dTemp);    // For now, assume upper/lower the same
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index a19899ce49dd1a30520be519bc8bbff979d92215..9fbce75b8057ce29a27a6a1f44e64b1f5f5b82f1 100644 (file)
@@ -47,25 +47,18 @@ INCLUDES
 #include <FGJSBBase.h>
 #include <input_output/FGXMLElement.h>
 #include <math/FGColumnVector3.h>
-// #include <FGAuxiliary.h>
+#include <models/FGAuxiliary.h>
 
 #ifdef FGFS
 #  include <simgear/compiler.h>
-#  include STL_STRING
-  SG_USING_STD(string);
-  SG_USING_STD(cerr);
-  SG_USING_STD(endl);
-  SG_USING_STD(cout);
-#else
-# include <string>
-  using std::string;
-# if !defined(sgi) || defined(__GNUC__) || (_COMPILER_VERSION >= 740)
-   using std::cerr;
-   using std::endl;
-   using std::cout;
-# endif
 #endif
 
+#include <string>
+using std::string;
+using std::cerr;
+using std::endl;
+using std::cout;
+
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 DEFINITIONS
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
@@ -83,49 +76,99 @@ CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 /** Models a fuel tank.
-    @author Jon Berndt
-    @see Akbar, Raza et al. "A Simple Analysis of Fuel Addition to the CWT of
-    747", California Institute of Technology, 1998
-<P>
+
+<h3>Fuel Temperature:</h3>
     Fuel temperature is calculated using the following assumptions:
-<P>
+
     Fuel temperature will only be calculated for tanks which have an initial fuel
     temperature specified in the configuration file.
-<P>
+
     The surface area of the tank is estimated from the capacity in pounds.  It
     is assumed that the tank is a wing tank with dimensions h by 4h by 10h. The
     volume of the tank is then 40(h)(h)(h). The area of the upper or lower 
     surface is then 40(h)(h).  The volume is also equal to the capacity divided
     by 49.368 lbs/cu-ft, for jet fuel.  The surface area of one side can then be
     derived from the tank's capacity.  
-<P>
+
     The heat capacity of jet fuel is assumed to be 900 Joules/lbm/K, and the 
     heat transfer factor of the tank is 1.115 Watts/sq-ft/K.
-<P>
-Configuration File Format
-<pre>
-\<AC_TANK TYPE="\<FUEL | OXIDIZER>" NUMBER="\<n>">
-  XLOC        \<x location>
-  YLOC        \<y location>
-  ZLOC        \<z location>
-  RADIUS      \<radius>
-  CAPACITY    \<capacity>
-  CONTENTS    \<contents>
-  TEMPERATURE \<fuel temperature>
-\</AC_TANK>
-</pre>
-Definition of the tank configuration file parameters:
-<pre>
-<b>TYPE</b> - One of FUEL or OXIDIZER.
-<b>XLOC</b> - Location of tank on aircraft's x-axis, inches.
-<b>YLOC</b> - Location of tank on aircraft's y-axis, inches.
-<b>ZLOC</b> - Location of tank on aircraft's z-axis, inches.
-<b>RADIUS</b> - Equivalent radius of tank, inches, for modeling slosh.
-<b>CAPACITY</b> - Capacity in pounds.
-<b>CONTENTS</b> - Initial contents in pounds.
-<b>TEMPERATURE</b> - Initial temperature in degrees Fahrenheit.
-</pre>
-  */
+
+<h3>Fuel Dump:</h3>
+
+    Fuel dumping is handled by the FGPropulsion class.  A standpipe can be defined
+    here for each tank which sets the level of contents (in pounds) which is not dumpable.
+    Default standpipe level is zero, making all contents dumpable.
+
+<h3>Fuel Transfer:</h3>
+
+    Fuel transfer is handled by the FGPropulsion class, however the contents of tanks
+    may be manipulated directly using the SetContents() function here, or via the property
+    tree at <tt>propulsion/tank[i]/contents-lbs</tt>, where i is the tank number (Tanks
+    are automatically numbered, starting at zero, in the order in which they are read in
+    the aircraft configuration file).  The latter method allows one to use a system of FCS
+    components to control tank contents. 
+
+<h3>Configuration File Format:</h3>
+
+@code
+<tank type="{FUEL | OXIDIZER}">
+  <location unit="{FT | M | IN}">
+    <x> {number} </x>
+    <y> {number} </y>
+    <z> {number} </z>
+  </location>
+  <drain_location unit="{FT | M | IN}">
+    <x> {number} </x>
+    <y> {number} </y>
+    <z> {number} </z>
+  </drain_location>
+  <radius unit="{FT | M}"> {number} </radius>
+  <capacity unit="{LBS | KG}"> {number} </capacity>
+  <contents unit="{LBS | KG}"> {number} </contents>
+  <temperature> {number} </temperature> <!-- must be degrees fahrenheit -->
+  <standpipe unit="{LBS | KG"}> {number} </standpipe>
+</tank>
+@endcode
+
+<h3>Definition of the tank configuration file parameters:</h3>
+
+- \b type - One of FUEL or OXIDIZER.  This is required.
+- \b radius - Equivalent radius of tank for modeling slosh, defaults to inches.
+- \b capacity - Capacity, defaults to pounds.
+- \b contents - Initial contents, defaults to pounds.
+- \b temperature - Initial temperature, defaults to degrees Fahrenheit.
+- \b standpipe - Minimum contents to which tank can dump, defaults to pounds.
+
+location:
+- \b x - Location of tank on aircraft's x-axis, defaults to inches.
+- \b y - Location of tank on aircraft's y-axis, defaults to inches.
+- \b z - Location of tank on aircraft's z-axis, defaults to inches.
+
+drain_location:
+- \b x - Location of tank drain on aircraft's x-axis, defaults to inches.
+- \b y - Location of tank drain on aircraft's y-axis, defaults to inches.
+- \b z - Location of tank drain on aircraft's z-axis, defaults to inches.
+
+<h3>Default values of the tank configuration file parameters:</h3>
+
+- \b type - ttUNKNOWN  (causes a load error in the propulsion configuration)
+- \b location, \b drain_location - both optional, but a warning message will
+be printed to the console if the location is not given
+- \b x - 0.0  (both full and drained CG locations)
+- \b y - 0.0  (both full and drained CG locations)
+- \b z - 0.0  (both full and drained CG locations)
+- \b radius - 0.0
+- \b capacity - 0.0
+- \b contents - 0.0
+- \b temperature - -9999.0
+- \b standpipe - 0.0
+
+    @author Jon Berndt, Dave Culp
+    @see Akbar, Raza et al. "A Simple Analysis of Fuel Addition to the CWT of
+    747", California Institute of Technology, 1998,
+    http://www.galcit.caltech.edu/EDL/projects/JetA/reports/lumped.pdf
+*/
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 CLASS DECLARATION
@@ -134,38 +177,72 @@ CLASS DECLARATION
 class FGTank : public FGJSBBase
 {
 public:
-  FGTank(FGFDMExec* exec, Element* el);
+  /** Constructor.
+      The constructor reads in the defining parameters from a configuration file.
+      @param exec a pointer to the base FGFDMExec instance.
+      @param el a pointer to the Tank element.
+      @param tank_number the tank number (zero based).
+  */
+  FGTank(FGFDMExec* exec, Element* el, int tank_number);
+  /// Destructor
   ~FGTank();
 
-  double Drain(double);
+  /** Removes fuel from the tank.
+      This function removes fuel from a tank. If the tank empties, it is
+      deselected.
+      @param used the amount of fuel used in lbs.
+      @return the remaining contents of the tank in lbs.
+  */
+  double Drain(double used);
+
+  /** Performs local, tanks-specific calculations, such as fuel temperature.
+      This function calculates the temperature of the fuel in the tank.
+      @param dt the time step for this model.
+      @return the current temperature in degrees Celsius.
+  */
   double Calculate(double dt);
+
+  /** Retrieves the type of tank: Fuel or Oxidizer.
+      @return the tank type, 0 for undefined, 1 for fuel, and 2 for oxidizer.
+  */
   int GetType(void) {return Type;}
+
+  /** Resets the tank parameters to the initial conditions */
+  void ResetToIC(void);
+
   bool GetSelected(void) {return Selected;}
   double GetPctFull(void) {return PctFull;}
-  double GetContents(void) {return Contents;}
+  double GetCapacity(void) {return Capacity;}
+  double GetContents(void) const {return Contents;}
   double GetTemperature_degC(void) {return Temperature;}
   double GetTemperature(void) {return CelsiusToFahrenheit(Temperature);}
-  const FGColumnVector3& GetXYZ(void) {return vXYZ;}
-  double GetXYZ(int idx) {return vXYZ(idx);}
+  double GetStandpipe(void) {return Standpipe;}
+  const FGColumnVector3 GetXYZ(void);
+  const double GetXYZ(int idx);
 
   double Fill(double amount);
   void SetContents(double amount);
   void SetTemperature(double temp) { Temperature = temp; }
+  void SetStandpipe(double amount) { Standpipe = amount; }
 
   enum TankType {ttUNKNOWN, ttFUEL, ttOXIDIZER};
 
 private:
   TankType Type;
+  int TankNumber;
   string type;
   FGColumnVector3 vXYZ;
+  FGColumnVector3 vXYZ_drain;
   double Capacity;
   double Radius;
   double PctFull;
-  double Contents;
+  double Contents, InitialContents;
   double Area;
-  double Temperature;      
+  double Temperature, InitialTemperature;
+  double Standpipe, InitialStandpipe;
   bool  Selected;
   FGAuxiliary* Auxiliary;
+  FGPropertyManager* PropertyManager;
   void Debug(int from);
 };
 }
index 02875b2a1de08da56f5a56ab5d57675062bbbec8..b802d6e8c36035849a1a4770ce797eea5e9dac50 100644 (file)
@@ -100,19 +100,6 @@ FGThruster::FGThruster(FGFDMExec *FDMExec, Element *el, int num ): FGForce(FDMEx
 
 FGThruster::~FGThruster()
 {
-  char property_name[80];
-  snprintf(property_name, 80, "propulsion/engine[%d]/pitch-angle-rad", EngineNum);
-  PropertyManager->Untie( property_name);
-  snprintf(property_name, 80, "propulsion/engine[%d]/yaw-angle-rad", EngineNum);
-  PropertyManager->Untie( property_name);
-
-  if (Type == ttDirect) // this is a direct thruster. At this time
-                                      // only a direct thruster can be reversed.
-  {
-    snprintf(property_name, 80, "propulsion/engine[%d]/reverser-angle-rad", EngineNum);
-    PropertyManager->Untie( property_name);
-  }
-
   Debug(1);
 }
 
index 7ab74a8758c18cdfe9ff10745b1645a57178424a..c2adf1998c73246c3b3504fe8c6fc4b59bf0ae9d 100644 (file)
@@ -61,6 +61,17 @@ CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
 /** Base class for specific thrusting devices such as propellers, nozzles, etc.
+
+<h3>reverser angle:</h3>
+
+    "Reverser angle" as used here is a way to manipulate the thrust vector,
+    along the thrust axis ONLY, during run time.  This should not be confused
+    with a thrust vectoring nozzle.  The angle is defined in radians, and is
+    used thus:  Final_thrust = cosine( reverser_angle ) * unmodified_thrust.  
+    Therefore a reverser angle of 0 results in no change, and a reverser angle
+    of 3.14 (pi) results in a completely reversed thrust vector.  An angle of
+    1.57 (pi/2) results in no thrust at all.
     @author Jon Berndt
     @version $Id$
     */
@@ -93,7 +104,7 @@ public:
   string GetName(void) {return Name;}
   void SetReverserAngle(double angle) {ReverserAngle = angle;}
   double GetReverserAngle(void) const {return ReverserAngle;}
-  virtual double GetRPM(void) { return 0.0; };
+  virtual double GetRPM(void) const { return 0.0; };
   double GetGearRatio(void) {return GearRatio; }
   virtual string GetThrusterLabels(int id, string delimeter);
   virtual string GetThrusterValues(int id, string delimeter);
index 09fda02577f2a803639e4df328edcd4a40029445..be8dc8a1908db918f6f0a76d0c0d5299ec1beb3e 100644 (file)
@@ -57,7 +57,19 @@ CLASS IMPLEMENTATION
 FGTurbine::FGTurbine(FGFDMExec* exec, Element *el, int engine_number)
   : FGEngine(exec, el, engine_number)
 {
-  SetDefaults();
+  Type = etTurbine;
+
+  MilThrust = MaxThrust = 10000.0;
+  TSFC = 0.8;
+  ATSFC = 1.7;
+  IdleN1 = 30.0;
+  IdleN2 = 60.0;
+  MaxN1 = MaxN2 = 100.0;
+  Augmented = AugMethod = Injected = 0;
+  BypassRatio = BleedDemand = 0.0;
+  IdleThrustLookup = MilThrustLookup = MaxThrustLookup = InjectionLookup = 0;
+
+  ResetToIC();
 
   Load(exec, el);
   Debug(0);
@@ -71,10 +83,24 @@ FGTurbine::~FGTurbine()
   delete MilThrustLookup;
   delete MaxThrustLookup;
   delete InjectionLookup;
-  unbind();
   Debug(1);
 }
 
+//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+void FGTurbine::ResetToIC(void)
+{
+  N1 = N2 = 0.0;
+  correctedTSFC = TSFC;
+  ThrottlePos = AugmentCmd = 0.0;
+  InletPosition = NozzlePosition = 1.0;
+  Stalled = Seized = Overtemp = Fire = Augmentation = Injection = Reversed = false;
+  Cutoff = true;
+  phase = tpOff;
+  EGT_degC = 0.0;
+  OilTemp_degK = (Auxiliary->GetTotalTemperature() - 491.69) * 0.5555556 + 273.0;
+}
+
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 // The main purpose of Calculate() is to determine what phase the engine should
 // be in, then call the corresponding function.
@@ -148,6 +174,7 @@ double FGTurbine::Off(void)
   NozzlePosition = Seek(&NozzlePosition, 1.0, 0.8, 0.8);
   EPR = Seek(&EPR, 1.0, 0.2, 0.2);
   Augmentation = false;
+  ConsumeFuel();  
   return 0.0;
 }
 
@@ -205,7 +232,12 @@ double FGTurbine::Run()
   }
 
   if ((Injected == 1) && Injection) {
-    thrust = thrust * InjectionLookup->GetValue();
+    InjectionTimer += dt;
+    if (InjectionTimer < InjectionTime) {
+       thrust = thrust * InjectionLookup->GetValue();
+    } else {
+       Injection = false;
+    }
   }
 
   ConsumeFuel();
@@ -294,10 +326,12 @@ double FGTurbine::Seize(void)
 
 double FGTurbine::Trim()
 {
-    double idlethrust, milthrust, thrust, tdiff;
+    double idlethrust, milthrust, thrust, tdiff, N2norm;
     idlethrust = MilThrust * IdleThrustLookup->GetValue();
     milthrust = (MilThrust - idlethrust) * MilThrustLookup->GetValue();
-    thrust = (idlethrust + (milthrust * ThrottlePos * ThrottlePos))
+    N2 = IdleN2 + ThrottlePos * N2_factor;
+    N2norm = (N2 - IdleN2) / N2_factor;
+    thrust = (idlethrust + (milthrust * N2norm * N2norm))
           * (1.0 - BleedDemand);
 
     if (AugMethod == 1) {
@@ -355,43 +389,6 @@ double FGTurbine::Seek(double *var, double target, double accel, double decel) {
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGTurbine::SetDefaults(void)
-{
-  N1 = N2 = 0.0;
-  Type = etTurbine;
-  MilThrust = 10000.0;
-  MaxThrust = 10000.0;
-  BypassRatio = 0.0;
-  TSFC = 0.8;
-  correctedTSFC = TSFC;
-  ATSFC = 1.7;
-  IdleN1 = 30.0;
-  IdleN2 = 60.0;
-  MaxN1 = 100.0;
-  MaxN2 = 100.0;
-  Augmented = 0;
-  AugMethod = 0;
-  Injected = 0;
-  BleedDemand = 0.0;
-  ThrottlePos = 0.0;
-  AugmentCmd = 0.0;
-  InletPosition = 1.0;
-  NozzlePosition = 1.0;
-  Augmentation = false;
-  Injection = false;
-  Reversed = false;
-  Cutoff = true;
-  phase = tpOff;
-  Stalled = false;
-  Seized = false;
-  Overtemp = false;
-  Fire = false;
-  EGT_degC = 0.0;
-  IdleThrustLookup = MilThrustLookup = MaxThrustLookup = InjectionLookup = 0;
-}
-
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
 bool FGTurbine::Load(FGFDMExec* exec, Element *el)
 {
   char property_prefix[80];
@@ -423,6 +420,8 @@ bool FGTurbine::Load(FGFDMExec* exec, Element *el)
     AugMethod = (int)el->FindElementValueAsNumber("augmethod");
   if (el->FindElement("injected"))
     Injected = (int)el->FindElementValueAsNumber("injected");
+  if (el->FindElement("injection-time"))
+    InjectionTime = el->FindElementValueAsNumber("injection-time");
 
   Element *function_element;
   string name;
@@ -496,20 +495,21 @@ void FGTurbine::bindmodel()
   PropertyManager->Tie( property_name, &N2);
   snprintf(property_name, 80, "propulsion/engine[%u]/thrust", EngineNumber);
   PropertyManager->Tie( property_name, this, &FGTurbine::GetThrust);
+  snprintf(property_name, 80, "propulsion/engine[%u]/injection_cmd", EngineNumber);
+  PropertyManager->Tie( property_name, (FGTurbine*)this, 
+                        &FGTurbine::GetInjection, &FGTurbine::SetInjection);
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 
-void FGTurbine::unbind()
-{
-  char property_name[80];
-
-  snprintf(property_name, 80, "propulsion/engine[%u]/n1", EngineNumber);
-  PropertyManager->Untie(property_name);
-  snprintf(property_name, 80, "propulsion/engine[%u]/n2", EngineNumber);
-  PropertyManager->Untie(property_name);
-  snprintf(property_name, 80, "propulsion/engine[%u]/thrust", EngineNumber);
-  PropertyManager->Untie(property_name);
+int FGTurbine::InitRunning(void) {
+  State->SuspendIntegration();
+  Cutoff=false;
+  Running=true;  
+  N2=16.0;
+  Calculate();
+  State->ResumeIntegration();
+  return phase==tpRun;
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
index 059f63153d69d0841ebe5037ffa14a9bb01629cc..752c622c3a094c3296424a9b895f25a77568ff91 100644 (file)
@@ -82,49 +82,68 @@ CLASS DOCUMENTATION
     Ignition is assumed to be on anytime the Cutoff control is set to false,
     therefore a seperate ignition system is not modeled.
 
-Configuration File Format
+<h3>Configuration File Format:</h3>
+@code
+ <turbine_engine name="{string}">
+  <milthrust unit="{LBS | N}"> {number} </milthrust>
+  <maxthrust unit="{LBS | N}"> {number} </maxthrust>
+  <bypassratio> {number} </bypassratio>
+  <bleed> {number} </bleed>
+  <tsfc> {number} </tsfc>
+  <atsfc> {number} </atsfc>
+  <idlen1> {number} </idlen1>
+  <idlen2> {number} </idlen2>
+  <maxn1> {number} </maxn1>
+  <maxn2> {number} </maxn2>
+  <augmented> {0 | 1} </augmented>
+  <augmethod> {0 | 1 | 2} </augmethod>
+  <injected> {0 | 1} </injected>
+  <injection-time> {number} </injection-time>
+ </turbine_engine>
+@endcode
+
+<h3>Definition of the turbine engine configuration file parameters:</h3>
+
 <pre>
-\<FG_TURBINE NAME="<name>">
-  MILTHRUST   \<thrust>
-  MAXTHRUST   \<thrust>
-  BYPASSRATIO \<bypass ratio>
-  TSFC        \<thrust specific fuel consumption>
-  ATSFC       \<afterburning thrust specific fuel consumption>
-  IDLEN1      \<idle N1>
-  IDLEN2      \<idle N2>
-  MAXN1       \<max N1>
-  MAXN2       \<max N2>
-  AUGMENTED   \<0|1>
-  AUGMETHOD   \<0|1>
-  INJECTED    \<0|1>
-  ...
-\</FG_TURBINE>
+  milthrust   - Maximum thrust, static, at sea level.
+  maxthrust   - Afterburning thrust, static, at sea level.
+  bypassratio - Ratio of bypass air flow to core air flow.
+  bleed       - Thrust reduction factor due to losses (0.0 to 1.0).
+  tsfc        - Thrust-specific fuel consumption at cruise, lbm/hr/lbf
+  atsfc       - Afterburning TSFC, lbm/hr/lbf
+  idlen1      - Fan rotor rpm (% of max) at idle
+  idlen2      - Core rotor rpm (% of max) at idle
+  maxn1       - Fan rotor rpm (% of max) at full throttle 
+  maxn2       - Core rotor rpm (% of max) at full throttle
+  augmented
+              0 = afterburner not installed
+              1 = afterburner installed
+  augmethod
+              0 = afterburner activated by property /engines/engine[n]/augmentation
+              1 = afterburner activated by pushing throttle above 99% position
+              2 = throttle range is expanded in the FCS, and values above 1.0 are afterburner range
+  injected
+              0 = Water injection not installed
+              1 = Water injection installed
+  injection-time - Time, in seconds, of water injection duration 
 </pre>
-Definition of the turbine engine configuration file parameters:
+
+<h3>NOTES:</h3>  
 <pre>
-<b>MILTHRUST</b> - Maximum thrust, static, at sea level, lbf.
-<b>MAXTHRUST</b> - Afterburning thrust, static, at sea level, lbf
-[this value will be ignored when AUGMENTED is zero (false)].
-<b>BYPASSRATIO</b> - Ratio of bypass air flow to core air flow.
-<b>TSFC</b> - Thrust-specific fuel consumption, lbm/hr/lbf
-[i.e. fuel flow divided by thrust].
-<b>ATSFC</b> - Afterburning TSFC, lbm/hr/lbf
-[this value will be ignored when AUGMENTED is zero (false)]
-<b>IDLEN1</b> - Fan rotor rpm (% of max) at idle
-<b>IDLEN2</b> - Core rotor rpm (% of max) at idle
-<b>MAXN1</b> - Fan rotor rpm (% of max) at full throttle [not always 100!]
-<b>MAXN2</b> - Core rotor rpm (% of max) at full throttle [not always 100!]
-<b>AUGMENTED</b>
-  0 == afterburner not installed
-  1 == afterburner installed
-<b>AUGMETHOD</b>
-  0 == afterburner activated by property /engines/engine[n]/augmentation
-  1 == afterburner activated by pushing throttle above 99% position
-  2 == throttle range is expanded in the FCS, and values above 1.0 are afterburner range
-  [this item will be ignored when AUGMENTED == 0]
-<b>INJECTED</b>
-  0 == Water injection not installed
-  1 == Water injection installed
+    Bypass ratio is used only to estimate engine acceleration time.  The
+    effect of bypass ratio on engine efficiency is already included in
+    the TSFC value.  Feel free to set this parameter (even for turbojets) to
+    whatever value gives a desired spool-up rate. Default value is 0.
+
+    The bleed factor is multiplied by thrust to give a resulting thrust
+    after losses.  This can represent losses due to bleed, or any other cause.
+    Default value is 0.  A common value would be 0.04.
+
+    Nozzle position, for variable area exhaust nozzles, is provided for users
+    needing to drive a nozzle gauge or animate a virtual nozzle.
+
+    This model can only be used with the "direct" thruster.  See the file:
+    /engine/direct.xml
 </pre>
     @author David P. Culp
     @version "$Id$"
@@ -140,7 +159,7 @@ public:
   /** Constructor
       @param Executive pointer to executive structure
       @param el pointer to the XML element representing the turbine engine
-      @param engine_number engine number*/
+      @param engine_number engine number  */
   FGTurbine(FGFDMExec* Executive, Element *el, int engine_number);
   /// Destructor
   ~FGTurbine();
@@ -151,6 +170,12 @@ public:
   double CalcFuelNeed(void);
   double GetPowerAvailable(void);
   double GetThrust(void) const {return Thrust;}
+  /** A lag filter.
+      Used to control the rate at which values are allowed to change.
+      @param var a pointer to a variable of type double
+      @param target the desired (target) value
+      @param accel the rate, per second, the value may increase
+      @param decel the rate, per second, the value may decrease    */
   double Seek(double* var, double target, double accel, double decel);
 
   phaseType GetPhase(void) { return phase; }
@@ -182,6 +207,8 @@ public:
   void SetBleedDemand(double bleedDemand) {BleedDemand = bleedDemand;}
   void SetReverse(bool reversed) { Reversed = reversed; }
   void SetCutoff(bool cutoff) { Cutoff = cutoff; }
+  int InitRunning(void);
+  void ResetToIC(void);
 
   string GetEngineLabels(string delimeter);
   string GetEngineValues(string delimeter);
@@ -230,6 +257,8 @@ private:
   double InletPosition;
   double NozzlePosition;
   double correctedTSFC;
+  double InjectionTimer;
+  double InjectionTime;
 
   double Off(void);
   double Run();
@@ -244,10 +273,8 @@ private:
   FGFunction *MaxThrustLookup;
   FGFunction *InjectionLookup;
 
-  void SetDefaults(void);
   bool Load(FGFDMExec *exec, Element *el);
   void bindmodel(void);
-  void unbind(void);
   void Debug(int from);
 
 };
index 6191e21492f80d535287117469c1ba8d020c3aab..d7be93c919ac4183e481e652e1984184ae1d571a 100755 (executable)
@@ -490,6 +490,15 @@ string FGTurboProp::GetEngineValues(string delimeter)
 }
 
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+int FGTurboProp::InitRunning(void) {
+  State->SuspendIntegration();
+  Cutoff=false;
+  Running=true;  
+  N2=16.0;
+  Calculate();
+  State->ResumeIntegration();
+  return phase==tpRun;
+}
 
 void FGTurboProp::bindmodel()
 {
@@ -506,21 +515,6 @@ void FGTurboProp::bindmodel()
 
 }
 
-//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-
-void FGTurboProp::unbind()
-{
-  char property_name[80];
-
-  snprintf(property_name, 80, "propulsion/engine[%u]/n1", EngineNumber);
-  PropertyManager->Untie(property_name);
-  snprintf(property_name, 80, "propulsion/engine[%u]/n2", EngineNumber);
-  PropertyManager->Untie(property_name);
-  snprintf(property_name, 80, "propulsion/engine[%u]/reverser", EngineNumber);
-  PropertyManager->Untie(property_name);
-}
-
-
 //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 //    The bitmasked value choices are as follows:
 //    unset: In this case (the default) JSBSim would only print
index 6ee080500f6e6950125dfc6ca6ace812e3729562..6501452b14bfb2b566e3fd7cf8ccde1099c5fb16 100755 (executable)
@@ -58,8 +58,33 @@ namespace JSBSim {
 CLASS DOCUMENTATION
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
 
-/** Turboprop engine model.
-
+/** Turboprop engine model.  For an example of this model in use see the file:
+    engine/engtm601.xml
+ <h3>Configuration parameters:</h3>
+<pre>
+milthrust   [LBS]
+idlen1      [%]
+maxn1       [%]
+betarangeend[%]
+    if ThrottleCmd < betarangeend/100.0 then engine power=idle, propeller pitch
+    is controled by ThrottleCmd (between MINPITCH and  REVERSEPITCH).
+    if ThrottleCmd > betarangeend/100.0 then engine power increases up to max reverse power
+reversemaxpower [%]
+    max engine power in reverse mode
+maxpower    [HP]
+psfc power specific fuel consumption [pph/HP] for N1=100%
+n1idle_max_delay [-] time constant for N1 change
+maxstartenginetime [sec]
+    after this time the automatic starting cycle is interrupted when the engine
+    doesn't start (0=automatic starting not present)
+startern1   [%]
+    when starting starter spin up engine to this spin
+ielumaxtorque [lb.ft]
+    if torque>ielumaxtorque limiters decrease the throttle
+    (ielu = Integrated Electronic Limiter Unit)
+itt_delay [-] time constant for ITT change
+    (ITT = Inter Turbine Temperature)
+</pre>
 */
 
 /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
@@ -121,7 +146,7 @@ public:
 
   inline void SetGeneratorPower(bool gp) { GeneratorPower=gp; }
   inline void SetCondition(bool c) { Condition=c; }
-
+  int InitRunning(void);
   string GetEngineLabels(string delimeter);  // added from Turbine 0.9.6
   string GetEngineValues(string delimeter);  // added from Turbine 0.9.6
 
@@ -165,8 +190,8 @@ private:
 
   double Idle_Max_Delay;       // time delay for exponencial
   double MaxPower;             // max engine power [HP]
-  double StarterN1;               // rotates of generator maked by starter [%]
-  double MaxStartingTime;           // maximal time for start [s] (-1 means not used)
+  double StarterN1;           // rotates of generator maked by starter [%]
+  double MaxStartingTime;      // maximal time for start [s] (-1 means not used)
   double Prop_RPM;             // propeller RPM
   double Velocity;
   double rho;
@@ -174,9 +199,9 @@ private:
 
   double Eng_HP;               // current engine power
 
-  double StartTime;               // engine strating time [s] (0 when start button pushed)
+  double StartTime;           // engine strating time [s] (0 when start button pushed)
 
-  double  ITT_Delay;            // time delay for exponencial grow of ITT
+  double  ITT_Delay;          // time delay for exponencial grow of ITT
   double  Eng_ITT_degC;
   double  Eng_Temperature;     // temperature inside engine
 
@@ -192,10 +217,9 @@ private:
   void SetDefaults(void);
   bool Load(FGFDMExec *exec, Element *el);
   void bindmodel(void);
-  void unbind(void);
   void Debug(int from);
 
-  FGTable* ITT_N1; // ITT temperature depending on throttle command
+  FGTable* ITT_N1;             // ITT temperature depending on throttle command
   FGTable* EnginePowerRPM_N1;
   FGTable* EnginePowerVC;
 };