]> git.mxchange.org Git - flightgear.git/commitdiff
Merge to get true base of James' recent gps changes
authorTim Moore <timoore33@gmail.com>
Sun, 28 Mar 2010 13:20:09 +0000 (15:20 +0200)
committerTim Moore <timoore33@gmail.com>
Sun, 28 Mar 2010 13:20:09 +0000 (15:20 +0200)
48 files changed:
Makefile.am
NEWS
configure.ac
docs-mini/README.digitalfilters
projects/VC7.1/FlightGear.vcproj
projects/VC90/FlightGear/FlightGear.vcproj
src/AIModel/AIAircraft.cxx
src/ATC/Makefile.am
src/ATC/atcutils.cxx [new file with mode: 0644]
src/ATC/atcutils.hxx [new file with mode: 0644]
src/ATC/trafficcontrol.cxx
src/ATC/trafficcontrol.hxx
src/Airports/apt_loader.cxx
src/Airports/apt_loader.hxx
src/Airports/groundnetwork.cxx
src/Autopilot/route_mgr.cxx
src/Autopilot/route_mgr.hxx
src/Autopilot/xmlauto.cxx
src/Autopilot/xmlauto.hxx
src/Cockpit/hud.cxx
src/Cockpit/hud_card.cxx
src/Cockpit/hud_gaug.cxx
src/Cockpit/hud_labl.cxx
src/Cockpit/hud_ladr.cxx
src/Cockpit/hud_rwy.cxx
src/Cockpit/hud_tbi.cxx
src/Cockpit/panel.cxx
src/Cockpit/panel_io.cxx
src/FDM/SP/ACMS.cxx
src/FDM/SP/MagicCarpet.cxx
src/FDM/UFO.cxx
src/FDM/flight.cxx
src/FDM/flight.hxx
src/GUI/Makefile.am
src/GUI/WaypointList.cxx [new file with mode: 0644]
src/GUI/WaypointList.hxx [new file with mode: 0644]
src/GUI/dialog.cxx
src/GUI/dialog.hxx
src/GUI/menubar.cxx
src/GUI/new_gui.cxx
src/Instrumentation/KLN89/kln89.cxx
src/Instrumentation/navradio.cxx
src/Main/Makefile.am
src/Main/fg_commands.cxx
src/Main/fg_init.cxx
src/Main/fg_props.cxx
src/Makefile.am
utils/Makefile.am

index 07fabe3e7159b6d317daf04cc4e5b0fc42b38675..c86f1c148db55d173441589ad76e6ec8145c694f 100644 (file)
@@ -8,8 +8,6 @@ SUBDIRS = \
 EXTRA_DIST = \
        acinclude.m4 \
        autogen.sh \
-       FlightGear.dsp \
-       FlightGear.dsw \
        projects \
        README \
        README.OpenAL \
@@ -19,7 +17,6 @@ EXTRA_DIST = \
        Thanks
 
 dist-hook:
-       (cd $(top_srcdir); $(HOME)/Projects/FlightGear/admin/am2dsp.pl)
        (cd $(top_srcdir); tar --exclude docs-mini/CVS --exclude hints/CVS \
                -cf - docs-mini ) | (cd $(distdir); tar xvf -)
        rm -rf `find $(distdir)/projects -name CVS`
@@ -55,7 +52,7 @@ data-tar:
        --exclude='*/Docs/source' \
         --exclude='*/Models/MNUAV' \
         --exclude='*/Models/Airspace' \
-       -cjvf source/FlightGear-data-$(VERSION).tar.bz2 \
+       -cjvf FlightGear-data-$(VERSION).tar.bz2 \
                data/AI \
                 data/Aircraft/Generic \
                 data/Aircraft/Instruments \
@@ -100,6 +97,7 @@ data-tar:
                data/preferences.xml \
                data/Protocol \
                data/README \
+               data/Scenery/Airports \
                data/Scenery/Objects \
                data/Scenery/Terrain \
                data/Shaders \
diff --git a/NEWS b/NEWS
index 0876a8d1d8cb5be112be1e9c40a381cce5eee48c..6590aeb49a452549b3c8f5a4be04394d96356715 100644 (file)
--- a/NEWS
+++ b/NEWS
@@ -1,5 +1,80 @@
-Version 1.99.5
-* October 30, 2008 (source code snapshot release)
+Version 2.0.0 - February 25, 2010
+
+  FlightGear 2.0.0. reflects the maturation of the OpenSceneGraph port
+  that started with the previous 1.9.0 release. In addition to many
+  internal code improvements, FlightGear 2.0.0. marks the introduction
+  of many new exciting improvements in the graphics and sound system,
+  as well as improved usability of key features, and improved behavior
+  of exsisting features. Highlights of this new version include:
+  Dramatic new 3D clouds, dramatic lighting conditions, improved
+  support for custom scenery, and many many new and detailed aircraft
+  models.
+
+  Sound 
+  * Complete overhaul of the sound code
+  * doppler effects
+  * distance attenuation
+  * 3D positional sound sources
+  * assignment of sound sources to external objects (i.e. AI controlled
+    aircraft)
+  * User selection of the sound device
+
+  Visual Effects
+  * Use of Shaders for dynamic textures
+  * Use of Effects files
+  * Improved 3D clouds
+  * Color changes based on humidity and other weather effects allow for very
+    dramatic lighting conditions
+  * Dynamic water textures
+  * Text animation based on OSGText
+
+  Usability
+  * Allow screenshots in more common file formats
+  * User selectable sound device
+  * More intuitive selection of the weather settings through the GUI and/or
+    commandline
+
+  Infrastructure
+  * Airport geometry data can be read from the scenery, allowing for more
+    flexible regeneration of terrain tiles
+
+  Internals
+  * Improved efficiency of the property tree
+  * A more efficient ground cache
+  * Many improvements to the route management code
+  * Removed many compiler warnings
+  * More realistic atmosphere model
+
+  Behavior
+  * More realistic ILS behavior
+  * Autopilot improvements
+  * A generic autobrake function
+  * Winds over mountainous areas cause up- and downdrafts that can be used
+    for gliding
+  * More realistic behavior of the route manager
+  * Wild fires, which can be extinguished by firefighter aircraft operating
+    across the multplayer server
+  * Navaid frequencies and radials can be transmitted to Atlas
+
+  Utilities
+  * A python script to visualize Yasim configuration files in Blender
+
+  AI
+  * Allow traffic departing and arriving at the same airport
+  * Add Ground Vehicles - including automobiles, trucks, articulated trucks,
+    trains (including high speed trains)
+  * ATC interactions between AI aircraft and ground controllers
+  * Performance characteristics of AI aircraft can be specified in a
+    performance database
+  * Push-back vehicles are available for a selected number of aircraft
+  * Add escorts for AI carrier - frigates, guided missile cruiser, amphibious
+    warfare ships now make up the Vinson Battle Group
+  * Improved radar functionality - now detects AI escorts etc.
+  * AI objects are now solid (i.e. users can collide with them)
+  * Some preliminary support for SID/STAR procedures for AI aircraft
+
+Version 1.9.0
+* December 20, 2008 (source code snapshot release)
 
 
 New in 0.9.10
index fda72f9fc2ef00d83d3f6c67465b3515db4a7723..85e9b58dcb22719eb07236c50db0a2fae6377a86 100644 (file)
@@ -175,6 +175,17 @@ else
 fi
 AM_CONDITIONAL(ENABLE_SP_FDM, test "x$enable_sp_fdms" != "xno")
 
+# Specify whether we want to compile ATCDCL.
+# default to with_atcdcl=yes
+AC_ARG_ENABLE(atcdcl, [  --enable-atcdcl                Compile and link the depricated atc/ai module], [enable_atcdcl="$enableval"] )
+if test "x$enable_atcdcl" != "xno"; then
+    AC_DEFINE([ENABLE_ATCDCL], 1, [Define to include old ATC/AI module])
+else
+    AC_DEFINE([ENABLE_ATCDCL], 0, [Define to include old ATC/AI module])
+fi
+AM_CONDITIONAL(ENABLE_ATCDCL, test "x$enable_atcdcl" != "xno")
+
+
 
 dnl EXPERIMENTAL generic event driven input device
 # defaults to no
@@ -218,6 +229,7 @@ if test "x$with_threads" = "xyes"; then
 fi
 AC_CHECK_HEADER(pthread.h)
 
+
 dnl Used by JSBSim to conditionally compile in fgfs interface code
 AC_DEFINE([FGFS], 1, [Define so that JSBSim compiles in 'library' mode])
 
@@ -300,7 +312,7 @@ AC_SEARCH_LIBS(clock_gettime, rt)
 base_LIBS="$LIBS"
 
 dnl Check for SDL or glut if enabled.
-AC_ARG_ENABLE(osgviewer, [  --enable-osgviewer                  Configure to use osgViewer(default)], [enable_osgviewer="$enableval"])
+AC_ARG_ENABLE(osgviewer, [  --enable-osgviewer             Configure to use osgViewer(default)], [enable_osgviewer="$enableval"])
 AC_ARG_ENABLE(sdl,  [  --enable-sdl                   Configure to use SDL], [enable_sdl="$enableval"])
 AC_ARG_ENABLE(glut, [  --enable-glut                  Configure to use GLUT], [enable_glut="$enableval"])
 AM_CONDITIONAL(USE_SDL, test "x$enable_sdl" = "xyes")
@@ -500,7 +512,7 @@ if test "x$ac_cv_header_simgear_version_h" != "xyes"; then
     exit
 fi
 
-AC_MSG_CHECKING([for SimGear 1.9.0 or newer])
+AC_MSG_CHECKING([for SimGear 2.0.0 or newer])
 AC_TRY_RUN([
 #include <stdio.h>
 
@@ -509,8 +521,8 @@ AC_TRY_RUN([
 #define STRINGIFY(X) XSTRINGIFY(X)
 #define XSTRINGIFY(X) #X
 
-#define MIN_MAJOR 1
-#define MIN_MINOR 9
+#define MIN_MAJOR 2
+#define MIN_MINOR 0
 #define MIN_MICRO 0
 
 int main() {
@@ -942,3 +954,8 @@ else
     echo "Include special purpose flight models: no"
 fi
 
+if test "x$enable_atcdcl" != "xno"; then
+    echo "Build depricated ATC/AI module: yes"
+else
+    echo "Build depricated ATC/AI module: no"
+fi
index ad7a26e2666f7e363933364adc2827c21d17c59e..dce9a80ddd479506b965b43f8548def99a8cb4a6 100644 (file)
@@ -27,6 +27,10 @@ The complete XML syntax for a InputValue is
   <max>infinity</max>
   <min>-infinity<min>
   <abs>false</abs>
+  <period>
+    <min>-180.0</min>
+    <max>-180.0</max>
+  </period>
 </some-element>
 
 The enclosing element <some-element> is the element defined in each filter, like <input>, <u_min>, 
@@ -124,7 +128,7 @@ other computations are completed.
     
 OutputValue           
 ==============================================================================
-Each filter drives one to many output properties. No scaling of offsetting is implemented
+Each filter drives one to many output properties. No scaling or offsetting is implemented
 for the output value, these should be done in the filter itself.
 The output properties are defined in the <output/> element by adding <property/> elements
 within the <output/> element. For just a single output property, the <property/> element
@@ -167,6 +171,8 @@ Example:
                           min or max value defaults to 0 (zero).
                           Note: <u_min> and <u_max> may also occour within a <config> element.
                           <min> and <max> may be used as a substitude for the corresponding u_xxx element.
+<period>      Complex     Define a periodical input or output value. The phase width is defined by the 
+                          child elements <min> and <max> which are of type InputValue
 
 Example: Limit the pilot's body temperature to a constant minimum of 36 and a maximum defined in
          /pilots/max-body-temperature-degc, initialized to 40.0
@@ -183,6 +189,17 @@ Implicit definition of the minimum value of 0 (zero) and defining a maximum of 1
   <u_max>100.0</u_max>
 </config>
 
+This defines the input or output as a periodic value with a phase width of 360, like 
+the compass rose.  Any value reaching the filter's input or leaving the filter at the 
+output will be transformed to fit into the given range by adding or substracting one phase 
+width of 360. Values of -270, 90 or 450 applied to this periodical element will allways 
+result in +90. A value of 630, 270 or -90 will be normalized to -90 in the given example.
+<period>
+  <min>-180.0</min>
+  <max>180.0</max>
+</period>
+
+
 <enable>      Complex     Define a condition to enable or disable the filter. For disabled
                           filters, no output computations are performed. Only enabled
                           filters fill the output properties. The default for undefined
index 9d0a96735e1ce98161a85c04fa718d5a7d8dc647..388947077cb05e8ad41e840d4dfdeed7569a7999 100755 (executable)
                        <File
                                RelativePath="..\..\src\GUI\SafeTexFont.hxx">
                        </File>
+                       <File RelativePath="..\..\..\src\GUI\WaypointList.cxx"></File>
+                       <File RelativePath="..\..\..\src\GUI\WaypointList.hxx"></File>
                </Filter>
                <Filter
                        Name="Lib_Input"
index d85b591de5b5e6fb35e3fdbcc7397a8302504c48..44905801ae85313bd759bca66467485f172d5401 100644 (file)
                                RelativePath="..\..\..\src\GUI\SafeTexFont.hxx"
                                >
                        </File>
+                       <File RelativePath="..\..\..\src\GUI\WaypointList.cxx"></File>
+                       <File RelativePath="..\..\..\src\GUI\WaypointList.hxx"></File>
                </Filter>
                <Filter
                        Name="Lib_Input"
index 68d7f46c44d4d0d605a63a2751d4ba59fe4ec859..eb8469fdece8dd419a721b5c7262caf3ddc9a6af 100644 (file)
@@ -447,15 +447,6 @@ void FGAIAircraft::announcePositionToController() {
         case 4:              //Take off tower controller
             if (trafficRef->getDepartureAirport()->getDynamics()) {
                 controller = trafficRef->getDepartureAirport()->getDynamics()->getTowerController();
-                //if (trafficRef->getDepartureAirport()->getId() == "EHAM") {
-                //string trns = trafficRef->getCallSign() + " at runway " + fp->getRunway() + 
-                //              ". Ready for departure. " + trafficRef->getFlightType() + " to " +
-                //              trafficRef->getArrivalAirport()->getId();
-                //fgSetString("/sim/messages/atc", trns.c_str());
-                //  if (controller == 0) {
-                //cerr << "Error in assigning controller at " << trafficRef->getDepartureAirport()->getId() << endl;
-                //}
-                //}
             } else {
                 cerr << "Error: Could not find Dynamics at airport : " << trafficRef->getDepartureAirport()->getId() << endl;
             }
index 32e4ced92eaa116817ca0780dd341fee3cb69406..35756c958bf13f648e844076052b0d53c8a4389b 100644 (file)
@@ -1,6 +1,7 @@
 noinst_LIBRARIES = libATC.a
 
 libATC_a_SOURCES = \
+       atcutils.cxx atcutils.hxx \
        trafficcontrol.cxx trafficcontrol.hxx 
 
 INCLUDES = -I$(top_srcdir) -I$(top_srcdir)/src
diff --git a/src/ATC/atcutils.cxx b/src/ATC/atcutils.cxx
new file mode 100644 (file)
index 0000000..12747c4
--- /dev/null
@@ -0,0 +1,372 @@
+// commlist.cxx -- comm frequency lookup class
+//
+// Written by David Luff and Alexander Kappes, started Jan 2003.
+// Based on navlist.cxx by Curtis Olson, started April 2000.
+//
+// Copyright (C) 2000  Curtis L. Olson - http://www.flightgear.org/~curt
+//
+// This program is free software; you can redistribute it and/or
+// modify it under the terms of the GNU 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
+// General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program; if not, write to the Free Software
+// Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.
+
+
+#ifdef HAVE_CONFIG_H
+#  include <config.h>
+#endif
+
+
+
+#include <simgear/debug/logstream.hxx>
+#include <simgear/misc/sg_path.hxx>
+#include <simgear/misc/sgstream.hxx>
+#include <simgear/math/sg_geodesy.hxx>
+#include <simgear/math/sg_random.h>
+#include <simgear/bucket/newbucket.hxx>
+#include <Airports/simple.hxx>
+
+#include "atcutils.hxx"
+
+#if !ENABLE_ATCDCL
+
+
+FGCommList *current_commlist;
+
+
+// Constructor
+FGCommList::FGCommList( void ) {
+      sg_srandom_time();
+}
+
+
+// Destructor
+FGCommList::~FGCommList( void ) {
+}
+
+
+// load the navaids and build the map
+bool FGCommList::init( const SGPath& path ) {
+/*
+    SGPath temp = path;
+    commlist_freq.erase(commlist_freq.begin(), commlist_freq.end());
+    commlist_bck.erase(commlist_bck.begin(), commlist_bck.end());
+    temp.append( "ATC/default.atis" );
+    LoadComms(temp);
+    temp = path;
+    temp.append( "ATC/default.tower" );
+    LoadComms(temp);
+    temp = path;
+    temp.append( "ATC/default.ground" );
+    LoadComms(temp);
+    temp = path;
+    temp.append( "ATC/default.approach" );
+    LoadComms(temp);
+    return true;*/
+}
+    
+
+bool FGCommList::LoadComms(const SGPath& path) {
+/*
+    sg_gzifstream fin( path.str() );
+    if ( !fin.is_open() ) {
+        SG_LOG( SG_GENERAL, SG_ALERT, "Cannot open file: " << path.str() );
+        exit(-1);
+    }
+    
+    // read in each line of the file
+    fin >> skipcomment;
+
+    while ( !fin.eof() ) {
+        ATCData a;
+        fin >> a;
+        if(a.type == INVALID) {
+            SG_LOG(SG_GENERAL, SG_DEBUG, "WARNING - INVALID type found in " << path.str() << '\n');
+        } else {        
+            // Push all stations onto frequency map
+            commlist_freq[a.freq].push_back(a);
+            
+            // Push non-atis stations onto bucket map as well
+            // In fact, push all stations onto bucket map for now so FGATCMgr::GetFrequency() works.
+            //if(a.type != ATIS and/or AWOS?) {
+                // get bucket number
+                SGBucket bucket(a.geod);
+                int bucknum = bucket.gen_index();
+                commlist_bck[bucknum].push_back(a);
+            //}
+        }
+        
+        fin >> skipcomment;
+    }
+    
+    fin.close();
+    return true;    
+*/
+}
+
+
+// query the database for the specified frequency, lon and lat are in
+// degrees, elev is in meters
+// If no atc_type is specified, it returns true if any non-invalid type is found
+// If atc_type is specifed, returns true only if the specified type is found
+bool FGCommList::FindByFreq(const SGGeod& aPos, double freq,
+                                               ATCData* ad, atc_type tp )
+{
+/*
+    comm_list_type stations;
+    stations = commlist_freq[kHz10(freq)];
+    comm_list_iterator current = stations.begin();
+    comm_list_iterator last = stations.end();
+    
+    // double az1, az2, s;
+    SGVec3d aircraft = SGVec3d::fromGeod(aPos);
+    const double orig_max_d = 1e100; 
+    double max_d = orig_max_d;
+    double d;
+    // TODO - at the moment this loop returns the first match found in range
+    // We want to return the closest match in the event of a frequency conflict
+    for ( ; current != last ; ++current ) {
+        d = distSqr(aircraft, current->cart);
+        
+        //cout << "  dist = " << sqrt(d)
+        //     << "  range = " << current->range * SG_NM_TO_METER << endl;
+        
+        // TODO - match up to twice the published range so we can model
+        // reduced signal strength
+        // NOTE The below is squared since we match to distance3Dsquared (above) to avoid a sqrt.
+        if ( d < (current->range * SG_NM_TO_METER 
+             * current->range * SG_NM_TO_METER ) ) {
+            //cout << "matched = " << current->ident << endl;
+            if((tp == INVALID) || (tp == (*current).type)) {
+                if(d < max_d) {
+                    max_d = d;
+                    *ad = *current;
+                }
+            }
+        }
+    }
+    
+    if(max_d < orig_max_d) {
+        return true;
+    } else {
+        return false;
+    }
+*/
+}
+
+int FGCommList::FindByPos(const SGGeod& aPos, double range, comm_list_type* stations, atc_type tp)
+{
+/*
+     // number of relevant stations found within range
+     int found = 0;
+     stations->erase(stations->begin(), stations->end());
+     
+     // get bucket number for plane position
+     SGBucket buck(aPos);
+     // get neigboring buckets
+     int bx = (int)( range*SG_NM_TO_METER / buck.get_width_m() / 2) + 1;
+     int by = (int)( range*SG_NM_TO_METER / buck.get_height_m() / 2 ) + 1;
+     
+     // loop over bucket range 
+     for ( int i=-bx; i<=bx; i++) {
+         for ( int j=-by; j<=by; j++) {
+             buck = sgBucketOffset(aPos.getLongitudeDeg(), aPos.getLatitudeDeg(), i, j);
+             long int bucket = buck.gen_index();
+             comm_map_const_iterator Fstations = commlist_bck.find(bucket);
+             if (Fstations == commlist_bck.end()) continue;
+             comm_list_const_iterator current = Fstations->second.begin();
+             comm_list_const_iterator last = Fstations->second.end();
+             
+             
+             // double az1, az2, s;
+             SGVec3d aircraft = SGVec3d::fromGeod(aPos);
+             double d;
+             for(; current != last; ++current) {
+                 if((current->type == tp) || (tp == INVALID)) {
+                     d = distSqr(aircraft, current->cart);
+                     // NOTE The below is squared since we match to distance3Dsquared (above) to avoid a sqrt.
+                     if ( d < (current->range * SG_NM_TO_METER
+                          * current->range * SG_NM_TO_METER ) ) {
+                         stations->push_back(*current);
+                         ++found;
+                     }
+                 }
+             }
+         }
+     }
+     return found;
+*/
+}
+
+
+// Returns the distance in meters to the closest station of a given type,
+// with the details written into ATCData& ad.  If no type is specifed simply
+// returns the distance to the closest station of any type.
+// Returns -9999 if no stations found within max_range in nautical miles (default 100 miles).
+// Note that the search algorithm starts at 10 miles and multiplies by 10 thereafter, so if
+// say 300 miles is specifed 10, then 100, then 1000 will be searched, breaking at first result 
+// and giving up after 1000.
+double FGCommList::FindClosest(const SGGeod& aPos, ATCData& ad, atc_type tp, double max_range) {
+/*
+    int num_stations = 0;
+    int range = 10;
+    comm_list_type stations;
+    comm_list_iterator itr;
+    double distance = -9999.0;
+    
+    while(num_stations == 0) {
+        num_stations = FindByPos(aPos, range, &stations, tp);
+        if(num_stations) {
+            double closest = max_range * SG_NM_TO_METER;
+            double tmp;
+            for(itr = stations.begin(); itr != stations.end(); ++itr) { 
+                ATCData ad2 = *itr;    
+                const FGAirport *a = fgFindAirportID(ad2.ident);
+                if (a) {
+                    tmp = dclGetHorizontalSeparation(ad2.geod, aPos);
+                    if(tmp <= closest) {
+                        closest = tmp;
+                        distance = tmp;
+                        ad = *itr;
+                    }
+                }
+            }
+            //cout << "Closest station is " << ad.ident << " at a range of " << distance << " meters\n";
+            return(distance);
+        }
+        if(range > max_range) {
+            break;
+        }
+        range *= 10;
+    }
+    return(-9999.0);
+*/
+}
+
+
+// Find by Airport code.
+// This is basically a wrapper for a call to the airport database to get the airport
+// position followed by a call to FindByPos(...)
+bool FGCommList::FindByCode( const string& ICAO, ATCData& ad, atc_type tp ) {
+/*
+    const FGAirport *a = fgFindAirportID( ICAO);
+    if ( a) {
+        comm_list_type stations;
+        int found = FindByPos(a->geod(), 10.0, &stations, tp);
+        if(found) {
+            comm_list_iterator itr = stations.begin();
+            while(itr != stations.end()) {
+                if(((*itr).ident == ICAO) && ((*itr).type == tp)) {
+                    ad = *itr;
+                    //cout << "FindByCode returns " << ICAO
+                    //     << "  type: " << tp
+                    //   << "  freq: " << itr->freq
+                    //   << endl;
+                    return true;
+                }
+                ++itr;
+            }
+        }
+    }
+    return false;
+*/
+}
+
+// TODO - this function should move somewhere else eventually!
+// Return an appropriate sequence number for an ATIS transmission.
+// Return sequence number + 2600 if sequence is unchanged since 
+// last time.
+int FGCommList::GetAtisSequence( const string& apt_id, 
+        const double tstamp, const int interval, const int special)
+{
+/*
+    atis_transmission_type tran;
+    
+    if(atislog.find(apt_id) == atislog.end()) { // New station
+      tran.tstamp = tstamp - interval;
+// Random number between 0 and 25 inclusive, i.e. 26 equiprobable outcomes:
+      tran.sequence = int(sg_random() * LTRS);
+      atislog[apt_id] = tran;
+      //cout << "New ATIS station: " << apt_id << " seq-1: "
+      //      << tran.sequence << endl;
+    } 
+
+// calculate the appropriate identifier and update the log
+    tran = atislog[apt_id];
+
+    int delta = int((tstamp - tran.tstamp) / interval);
+    tran.tstamp += delta * interval;
+    if (special && !delta) delta++;     // a "special" ATIS update is required
+    tran.sequence = (tran.sequence + delta) % LTRS;
+    atislog[apt_id] = tran;
+    //if (delta) cout << "New ATIS sequence: " << tran.sequence
+    //      << "  Delta: " << delta << endl;
+    return(tran.sequence + (delta ? 0 : LTRS*1000));
+*/
+}
+/*****************************************************************************
+ * FGKln89AlignedProjection 
+ ****************************************************************************/
+
+FGKln89AlignedProjection::FGKln89AlignedProjection() {
+    _origin.setLatitudeRad(0);
+    _origin.setLongitudeRad(0);
+    _origin.setElevationM(0);
+    _correction_factor = cos(_origin.getLatitudeRad());
+}
+
+FGKln89AlignedProjection::FGKln89AlignedProjection(const SGGeod& centre, double heading) {
+    _origin = centre;
+    _theta = heading * SG_DEGREES_TO_RADIANS;
+    _correction_factor = cos(_origin.getLatitudeRad());
+}
+
+FGKln89AlignedProjection::~FGKln89AlignedProjection() {
+}
+
+void FGKln89AlignedProjection::Init(const SGGeod& centre, double heading) {
+    _origin = centre;
+    _theta = heading * SG_DEGREES_TO_RADIANS;
+    _correction_factor = cos(_origin.getLatitudeRad());
+}
+
+SGVec3d FGKln89AlignedProjection::ConvertToLocal(const SGGeod& pt) {
+    // convert from lat/lon to orthogonal
+    double delta_lat = pt.getLatitudeRad() - _origin.getLatitudeRad();
+    double delta_lon = pt.getLongitudeRad() - _origin.getLongitudeRad();
+    double y = sin(delta_lat) * SG_EQUATORIAL_RADIUS_M;
+    double x = sin(delta_lon) * SG_EQUATORIAL_RADIUS_M * _correction_factor;
+
+    // Align
+    if(_theta != 0.0) {
+        double xbar = x;
+        x = x*cos(_theta) - y*sin(_theta);
+        y = (xbar*sin(_theta)) + (y*cos(_theta));
+    }
+
+    return SGVec3d(x, y, pt.getElevationM());
+}
+
+SGGeod FGKln89AlignedProjection::ConvertFromLocal(const SGVec3d& pt) {
+    // de-align
+    double thi = _theta * -1.0;
+    double x = pt.x()*cos(thi) - pt.y()*sin(thi);
+    double y = (pt.x()*sin(thi)) + (pt.y()*cos(thi));
+
+    // convert from orthogonal to lat/lon
+    double delta_lat = asin(y / SG_EQUATORIAL_RADIUS_M);
+    double delta_lon = asin(x / SG_EQUATORIAL_RADIUS_M) / _correction_factor;
+
+    return SGGeod::fromRadM(_origin.getLongitudeRad()+delta_lon, _origin.getLatitudeRad()+delta_lat, pt.z());
+}
+
+#endif // #ENABLE_ATCDCL
\ No newline at end of file
diff --git a/src/ATC/atcutils.hxx b/src/ATC/atcutils.hxx
new file mode 100644 (file)
index 0000000..e26d204
--- /dev/null
@@ -0,0 +1,185 @@
+// atcutils.hxx 
+//
+// This file contains a collection of classes from David Luff's
+// AI/ATC code that are shared by non-AI parts of FlightGear.
+// more specifcially, it contains implementations of FGCommList and
+// FGATCAlign
+//
+// Written by David Luff and Alexander Kappes, started Jan 2003.
+// Based on navlist.hxx by Curtis Olson, started April 2000.
+//
+// Copyright (C) 2000  Curtis L. Olson - http://www.flightgear.org/~curt
+//
+// This program is free software; you can redistribute it and/or
+// modify it under the terms of the GNU 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
+// General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program; if not, write to the Free Software
+// Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.
+
+/*****************************************************************
+*
+* FGCommList is used to store communication frequency information
+* for the ATC and AI subsystems.  Two maps are maintained - one
+* searchable by location and one searchable by frequency.  The
+* data structure returned from the search is the ATCData struct
+* defined in ATC.hxx, containing location, frequency, name, range
+* and type of the returned station.
+*
+******************************************************************/
+
+#ifndef _FG_ATCUTILS_HXX
+#define _FG_ATCUTILS_HXX
+
+
+
+#include <simgear/compiler.h>
+
+#include <map>
+#include <list>
+#include <string>
+
+//#include "ATC.hxx"
+//#include "atis.hxx"
+
+#if !ENABLE_ATCDCL
+
+class SGPath;
+class ATCData;
+
+// Possible types of ATC type that the radios may be tuned to.
+// INVALID implies not tuned in to anything.
+enum atc_type {
+       AWOS,
+       ATIS,
+       GROUND,
+       TOWER,
+       APPROACH,
+       DEPARTURE,
+       ENROUTE,
+  INVALID       /* must be last element;  see ATC_NUM_TYPES */
+};
+
+
+// A list of ATC stations
+typedef std::list < ATCData > comm_list_type;
+typedef comm_list_type::iterator comm_list_iterator;
+typedef comm_list_type::const_iterator comm_list_const_iterator;
+
+// A map of ATC station lists
+typedef std::map < int, comm_list_type > comm_map_type;
+typedef comm_map_type::iterator comm_map_iterator;
+typedef comm_map_type::const_iterator comm_map_const_iterator;
+
+
+class FGCommList {
+    
+public:
+
+    FGCommList();
+    ~FGCommList();
+
+    // load all comm frequencies and build the map
+    bool init( const SGPath& path );
+
+    // query the database for the specified frequency, lon and lat are
+    // If no atc_type is specified, it returns true if any non-invalid type is found.
+    // If atc_type is specifed, returns true only if the specified type is found.
+    // Returns the station closest to the supplied position.
+    // The data found is written into the passed-in ATCData structure.
+    bool FindByFreq(const SGGeod& aPos, double freq, ATCData* ad, atc_type tp = INVALID );
+    
+    // query the database by location, lon and lat are in degrees, elev is in meters, range is in nautical miles.
+    // Returns the number of stations of the specified atc_type tp that are in range of the position defined by 
+    // lon, lat and elev, and pushes them into stations.
+    // If no atc_type is specifed, returns the number of all stations in range, and pushes them into stations
+    // ** stations is erased before use **
+    int FindByPos(const SGGeod& aPos, double range, comm_list_type* stations, atc_type tp = INVALID );
+    
+    // Returns the distance in meters to the closest station of a given type,
+    // with the details written into ATCData& ad.  If no type is specifed simply
+    // returns the distance to the closest station of any type.
+    // Returns -9999 if no stations found within max_range in nautical miles (default 100 miles).
+    // Note that the search algorithm starts at 10 miles and multiplies by 10 thereafter, so if
+    // say 300 miles is specifed 10, then 100, then 1000 will be searched, breaking at first result 
+    // and giving up after 1000.
+    // !!!Be warned that searching anything over 100 miles will pause the sim unacceptably!!!
+    //  (The ability to search longer ranges should be used during init only).
+    double FindClosest(const SGGeod& aPos, ATCData& ad, atc_type tp = INVALID, double max_range = 100.0 );
+    
+    // Find by Airport code.
+    bool FindByCode( const std::string& ICAO, ATCData& ad, atc_type tp = INVALID );
+
+    // Return the sequence letter for an ATIS transmission given transmission time and airport id
+    // This maybe should get moved somewhere else!!
+    int GetAtisSequence( const std::string& apt_id, const double tstamp, 
+                    const int interval, const int flush=0);
+    
+    // Comm stations mapped by frequency
+    //comm_map_type commlist_freq;    
+    
+    // Comm stations mapped by bucket
+    //comm_map_type commlist_bck;
+
+    // Load comms from a specified path (which must include the filename)   
+private:
+
+    bool LoadComms(const SGPath& path);
+
+//----------- This stuff is left over from atislist.[ch]xx and maybe should move somewhere else
+    // Add structure and map for storing a log of atis transmissions
+    // made in this session of FlightGear.  This allows the callsign
+    // to be allocated correctly wrt time.
+    //typedef struct {
+    //        double tstamp;
+    //    int sequence;
+    //} atis_transmission_type;
+
+    //typedef std::map < std::string, atis_transmission_type > atis_log_type;
+    //typedef atis_log_type::iterator atis_log_iterator;
+    //typedef atis_log_type::const_iterator atis_log_const_iterator;
+
+    //atis_log_type atislog;
+//-----------------------------------------------------------------------------------------------
+
+};
+
+
+extern FGCommList *current_commlist;
+
+// FGATCAlignedProjection - a class to project an area local to a runway onto an orthogonal co-ordinate system
+// with the origin at the threshold and the runway aligned with the y axis.
+class FGKln89AlignedProjection {
+
+public:
+    FGKln89AlignedProjection();
+    FGKln89AlignedProjection(const SGGeod& centre, double heading);
+    ~FGKln89AlignedProjection();
+
+    void Init(const SGGeod& centre, double heading);
+
+    // Convert a lat/lon co-ordinate (degrees) to the local projection (meters)
+    SGVec3d ConvertToLocal(const SGGeod& pt);
+
+    // Convert a local projection co-ordinate (meters) to lat/lon (degrees)
+    SGGeod ConvertFromLocal(const SGVec3d& pt);
+
+private:
+    SGGeod _origin;    // lat/lon of local area origin (the threshold)
+    double _theta;     // the rotation angle for alignment in radians
+    double _correction_factor; // Reduction in surface distance per degree of longitude due to latitude.  Saves having to do a cos() every call.
+
+};
+
+#endif // #if ENABLE_ATCDCL
+
+#endif // _FG_ATCUTILS_HXX
+
+
index af0f729e7225f839b7f018f7f09b3f1117602b21..ef5a0a01f8dac2c2d767c1c1b040164a3d4dc093 100644 (file)
@@ -265,7 +265,7 @@ bool FGTrafficRecord::isOpposing (FGGroundNetwork *net, FGTrafficRecord &other,
          if (other.intentions.size())
            {
              for (intVecIterator j = other.intentions.begin(); j != other.intentions.end(); j++)
-               {  
+               {
                  // cerr << "Current segment 1 " << (*i) << endl;
                  if ((*i) > 0) {
                    if ((opp = net->findSegment(*i)->opposite()))
@@ -418,7 +418,7 @@ void FGATCController::transmit(FGTrafficRecord *rec, AtcMsgId msgId, AtcMsgDir m
           // Assign SID, if necessery (TODO)
           case MSG_PERMIT_ENGINE_START:
                taxiFreqStr = formatATCFrequency3_2(taxiFreq);
-               
+
                heading = rec->getAircraft()->getTrafficRef()->getCourse();
                fltType = rec->getAircraft()->getTrafficRef()->getFlightType();
                rwyClass= rec->getAircraft()->GetFlightPlan()->getRunwayClassFromTrafficType(fltType);
@@ -479,7 +479,6 @@ void FGATCController::transmit(FGTrafficRecord *rec, AtcMsgId msgId, AtcMsgDir m
     // Display ATC message only when one of the radios is tuned
     // the relevant frequency.
     // Note that distance attenuation is currently not yet implemented
-    //cerr << "Transmitting " << text << " at " << stationFreq;
     if ((onBoardRadioFreqI0 == stationFreq) || (onBoardRadioFreqI1 == stationFreq)) {
         if (rec->allowTransmissions()) {
             fgSetString("/sim/messages/atc", text.c_str());
@@ -493,6 +492,8 @@ string FGATCController::formatATCFrequency3_2(int freq) {
     return string(buffer);
 }
 
+// TODO: Set transponder codes according to real-world routes.
+// The current version just returns a random string of four octal numbers. 
 string FGATCController::genTransponderCode(string fltRules) {
     if (fltRules == "VFR") {
         return string("1200");
index 93217cc127c8ef85e2430eef6c77d02ce076d7cc..027f63d7ff6be2db374f29e4f50d1a5de1b85691 100644 (file)
@@ -45,7 +45,6 @@ typedef vector<int>::iterator intVecIterator;
 
 class FGAIFlightPlan;  // forward reference
 class FGGroundNetwork; // forward reference
-//class FGAISchedule;    // forward reference
 class FGAIAircraft;    // forward reference
 
 /**************************************************************************************
index af9319ae35cf81ba6a79ebe65ead10aa148089be..8984214d994f305d35a7fd8cccbdff80ff496cf3 100644 (file)
 #include "simple.hxx"
 #include "runways.hxx"
 #include "pavement.hxx"
-#include <ATCDCL/commlist.hxx>
+#if ENABLE_ATCDCL
+#    include <ATCDCL/commlist.hxx>
+#else
+  #include <ATC/atcutils.hxx>
+#endif
 
 #include <iostream>
 
@@ -75,6 +79,8 @@ public:
      last_apt_type("")
   {}
 
+
+
   void parseAPT(const string &aptdb_file, FGCommList *comm_list)
   {
     sg_gzifstream in( aptdb_file );
@@ -155,7 +161,9 @@ public:
       } else if ( line_id == 0 ) {
           // ??
       } else if ( line_id == 50 ) {
+
         parseATISLine(comm_list, simgear::strutils::split(line));
+
       } else if ( line_id >= 51 && line_id <= 56 ) {
         // other frequency entries (ignore)
       } else if ( line_id == 110 ) {
@@ -461,7 +469,7 @@ private:
       pvt->addNode(pos, num == 113);
     }
   }
-  
+
   void parseATISLine(FGCommList *comm_list, const vector<string>& token) 
   {
     if ( rwy_count <= 0 ) {
@@ -478,6 +486,7 @@ private:
            // 50 11770 AWOS 3
  // This code parallels code found in "operator>>" in ATC.hxx;
  // FIXME: unify the code.      
+#if ENABLE_ATCDCL
     ATCData a;
     a.geod = SGGeod::fromDegFt(rwy_lon_accum / (double)rwy_count, 
       rwy_lat_accum / (double)rwy_count, last_apt_elev);
@@ -496,6 +505,8 @@ private:
     SGBucket bucket(a.geod);
     int bucknum = bucket.gen_index();
     comm_list->commlist_bck[bucknum].push_back(a);
+#else
+#endif
 #if 0
    SG_LOG( SG_GENERAL, SG_ALERT, 
      "Loaded ATIS/AWOS for airport: " << a.ident
@@ -505,8 +516,10 @@ private:
     << "  type: " << a.type );
 #endif
   }
+
 };
 
+
 // Load the airport data base from the specified aptdb file.  The
 // metar file is used to mark the airports as having metar available
 // or not.
@@ -515,9 +528,7 @@ bool fgAirportDBLoad( const string &aptdb_file,
 {
 
    APTLoader ld;
-
    ld.parseAPT(aptdb_file, comm_list);
-
     //
     // Load the metar.dat file and update apt db with stations that
     // have metar data.
index 54596e8d85bf37e07a36547ecc09acc68686a721..7e2405638dffe21c05d866361d4419dac2ccd77c 100644 (file)
@@ -35,8 +35,8 @@ class FGCommList;
 // Load the airport data base from the specified aptdb file.  The
 // metar file is used to mark the airports as having metar available
 // or not.
+
 bool fgAirportDBLoad( const std::string &aptdb_file, 
         FGCommList *comm_list, const std::string &metar_file );
 
-
 #endif // _FG_APT_LOADER_HXX
index 054741ac4374de577c796f2bf0570bf24710605d..321a3af68833c7212d8f67d037e6b3e651d872e5 100644 (file)
@@ -508,6 +508,13 @@ void FGGroundNetwork::signOff(int id) {
 
 void FGGroundNetwork::update(int id, double lat, double lon, double heading, double speed, double alt, 
                             double dt) {
+   // Check whether aircraft are on hold due to a preceding pushback. If so, make sure to 
+   // Transmit air-to-ground "Ready to taxi request:
+   // Transmit ground to air approval / hold
+   // Transmit confirmation ... 
+   // Probably use a status mechanism similar to the Engine start procedure in the startup controller.
+
+
    TrafficVectorIterator i = activeTraffic.begin();
    // Search search if the current id has an entry
    // This might be faster using a map instead of a vector, but let's start by taking a safe route
index d6d65cc208331f6e59f1cb940ffeae4dc518ada9..64263dc25749eedfc0913bef2722a6548293da71 100644 (file)
@@ -172,6 +172,7 @@ void FGRouteMgr::init() {
   wpn->getChild("eta", 0, true);
   
   _route->clear();
+  _route->set_current(0);
   update_mirror();
   
   _pathNode = fgGetNode(RM "file-path", 0, true);
@@ -285,18 +286,33 @@ void FGRouteMgr::setETAPropertyFromDistance(SGPropertyNode_ptr aProp, double aDi
     aProp->setStringValue( eta_str );
 }
 
-void FGRouteMgr::add_waypoint( const SGWayPoint& wp, int n ) {
+void FGRouteMgr::add_waypoint( const SGWayPoint& wp, int n )
+{
   _route->add_waypoint( wp, n );
     
-  if (_route->current_index() > n) {
+  if ((n >= 0) && (_route->current_index() > n)) {
     _route->set_current(_route->current_index() + 1);
   }
   
+  waypointsChanged();
+}
+
+void FGRouteMgr::waypointsChanged()
+{
+  double routeDistanceNm = _route->total_distance() * SG_METER_TO_NM;
+  totalDistance->setDoubleValue(routeDistanceNm);
+  double cruiseSpeedKts = cruise->getDoubleValue("speed", 0.0);
+  if (cruiseSpeedKts > 1.0) {
+    // very very crude approximation, doesn't allow for climb / descent
+    // performance or anything else at all
+    ete->setDoubleValue(routeDistanceNm / cruiseSpeedKts * (60.0 * 60.0));
+  }
+
   update_mirror();
   _edited->fireValueChanged();
+  checkFinished();
 }
 
-
 SGWayPoint FGRouteMgr::pop_waypoint( int n ) {
   if ( _route->size() <= 0 ) {
     return SGWayPoint();
@@ -313,10 +329,7 @@ SGWayPoint FGRouteMgr::pop_waypoint( int n ) {
   SGWayPoint wp = _route->get_waypoint(n);
   _route->delete_waypoint(n);
     
-  update_mirror();
-  _edited->fireValueChanged();
-  checkFinished();
-  
+  waypointsChanged();
   return wp;
 }
 
@@ -467,9 +480,15 @@ void FGRouteMgr::InputListener::valueChanged(SGPropertyNode *prop)
       mgr->loadRoute();
     } else if (!strcmp(s, "@SAVE")) {
       mgr->saveRoute();
-    } else if (!strcmp(s, "@POP"))
-        mgr->pop_waypoint(0);
-    else if (!strncmp(s, "@DELETE", 7))
+    } else if (!strcmp(s, "@POP")) {
+      SG_LOG(SG_AUTOPILOT, SG_WARN, "route-manager @POP command is deprecated");
+    } else if (!strcmp(s, "@NEXT")) {
+      mgr->jumpToIndex(mgr->currentWaypoint() + 1);
+    } else if (!strcmp(s, "@PREVIOUS")) {
+      mgr->jumpToIndex(mgr->currentWaypoint() - 1);
+    } else if (!strncmp(s, "@JUMP", 5)) {
+      mgr->jumpToIndex(atoi(s + 5));
+    } else if (!strncmp(s, "@DELETE", 7))
         mgr->pop_waypoint(atoi(s + 7));
     else if (!strncmp(s, "@INSERT", 7)) {
         char *r;
@@ -529,16 +548,6 @@ bool FGRouteMgr::activate()
   }
 
   _route->set_current(0);
-  
-  double routeDistanceNm = _route->total_distance() * SG_METER_TO_NM;
-  totalDistance->setDoubleValue(routeDistanceNm);
-  double cruiseSpeedKts = cruise->getDoubleValue("speed", 0.0);
-  if (cruiseSpeedKts > 1.0) {
-    // very very crude approximation, doesn't allow for climb / descent
-    // performance or anything else at all
-    ete->setDoubleValue(routeDistanceNm / cruiseSpeedKts * (60.0 * 60.0));
-  }
-  
   active->setBoolValue(true);
   SG_LOG(SG_AUTOPILOT, SG_INFO, "route-manager, activate route ok");
   return true;
@@ -576,11 +585,6 @@ bool FGRouteMgr::checkFinished()
 
 void FGRouteMgr::jumpToIndex(int index)
 {
-  if (!active->getBoolValue()) {
-    SG_LOG(SG_AUTOPILOT, SG_ALERT, "trying to sequence waypoints with no active route");
-    return;
-  }
-
   if ((index < 0) || (index >= _route->size())) {
     SG_LOG(SG_AUTOPILOT, SG_ALERT, "passed invalid index (" << 
       index << ") to FGRouteMgr::jumpToIndex");
@@ -637,6 +641,16 @@ int FGRouteMgr::currentWaypoint() const
   return _route->current_index();
 }
 
+void FGRouteMgr::setWaypointTargetAltitudeFt(unsigned int index, int altFt)
+{
+  SGWayPoint wp = _route->get_waypoint(index);
+  wp.setTargetAltFt(altFt);
+  // simplest way to update a waypoint is to remove and re-add it
+  _route->delete_waypoint(index);
+  _route->add_waypoint(wp, index);
+  waypointsChanged();
+}
+
 void FGRouteMgr::saveRoute()
 {
   SGPath path(_pathNode->getStringValue());
index b096572591533419f4a429cedde07d820c64240a..a8168924807a5ec582759dfd63becd271d527ce6 100644 (file)
@@ -113,6 +113,12 @@ private:
      */
     SGWayPoint* make_waypoint(const string& target);
     
+    /**
+     * Helper to keep various pieces of state in sync when the SGRoute is
+     * modified (waypoints added, inserted, removed). Notably, this fires the
+     * 'edited' signal.
+     */
+    void waypointsChanged();
     
     void update_mirror();
     
@@ -188,6 +194,11 @@ public:
      */
     void jumpToIndex(int index);
     
+    /**
+     * 
+     */
+    void setWaypointTargetAltitudeFt(unsigned int index, int altFt);
+    
     void saveRoute();
     void loadRoute();
 };
index 6d542855787ee720bc80f7a92336bdac8d13e37a..119083f66c7738b29b9a38d3ff8df91c5bb7939a 100644 (file)
 using std::cout;
 using std::endl;
 
+FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
+{
+  SGPropertyNode_ptr minNode = root->getChild( "min" );
+  SGPropertyNode_ptr maxNode = root->getChild( "max" );
+  if( minNode == NULL || maxNode == NULL ) {
+    SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
+  } else {
+    minPeriod = new FGXMLAutoInput( minNode );
+    maxPeriod = new FGXMLAutoInput( maxNode );
+  }
+}
+
+double FGPeriodicalValue::normalize( double value )
+{
+  if( !(minPeriod && maxPeriod )) return value;
+
+  double p1 = minPeriod->get_value();
+  double p2 = maxPeriod->get_value();
+
+  double min = std::min<double>(p1,p2);
+  double max = std::max<double>(p1,p2);
+  double phase = fabs(max - min);
+
+  if( phase > SGLimitsd::min() ) {
+    while( value < min ) value += phase;
+    while( value >= max ) value -= phase;
+  } else {
+    value = min; // phase is zero
+  }
+
+  return value;
+}
+
 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
   value(0.0),
   abs(false),
-  property(NULL),
-  offset(NULL),
-  scale(NULL),
-  min(NULL),
-  max(NULL),
   _condition(NULL) 
 {
   parse( node, value, offset, scale );
@@ -62,6 +90,7 @@ void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffs
     scale = NULL;
     min = NULL;
     max = NULL;
+    periodical = NULL;
 
     if( node == NULL )
         return;
@@ -69,7 +98,7 @@ void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffs
     SGPropertyNode * n;
 
     if( (n = node->getChild("condition")) != NULL ) {
-        _condition = sgReadCondition(node, n);
+        _condition = sgReadCondition(fgGetNode("/"), n);
     }
 
     if( (n = node->getChild( "scale" )) != NULL ) {
@@ -92,6 +121,10 @@ void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffs
       abs = n->getBoolValue();
     }
 
+    if( (n = node->getChild( "period" )) != NULL ) {
+      periodical = new FGPeriodicalValue( n );
+    }
+
     SGPropertyNode *valueNode = node->getChild( "value" );
     if ( valueNode != NULL ) {
         value = valueNode->getDoubleValue();
@@ -161,6 +194,10 @@ double FGXMLAutoInput::get_value()
         if( value > m )
             value = m;
     }
+
+    if( periodical ) {
+      value = periodical->normalize( value );
+    }
     
     return abs ? fabs(value) : value;
 }
@@ -200,7 +237,7 @@ void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
       debug = child->getBoolValue();
     } else if ( cname == "enable" ) {
       if( (prop = child->getChild("condition")) != NULL ) {
-        _condition = sgReadCondition(child, prop);
+        _condition = sgReadCondition(fgGetNode("/"), prop);
       } else {
          if ( (prop = child->getChild( "prop" )) != NULL ) {
              enable_prop = fgGetNode( prop->getStringValue(), true );
@@ -246,6 +283,8 @@ void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
         umaxInput.push_back( new FGXMLAutoInput( child ) );
     } else if ( cname == "u_max" ) {
         umaxInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "period" ) {
+      periodical = new FGPeriodicalValue( child );
     } else {
       SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:" 
         << cname << " in section " << name);
@@ -314,6 +353,11 @@ void FGXMLAutoComponent::do_feedback_if_disabled()
 
 double FGXMLAutoComponent::clamp( double value )
 {
+    //If this is a periodical value, normalize it into our domain 
+    // before clamping
+    if( periodical )
+      value = periodical->normalize( value );
+
     // clamp, if either min or max is defined
     if( uminInput.size() + umaxInput.size() > 0 ) {
         double d = umaxInput.get_value( 0.0 );
@@ -685,6 +729,10 @@ bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
       filterType = gain;
     } else if (val == "reciprocal") {
       filterType = reciprocal;
+    } else if (val == "differential") {
+      filterType = differential;
+      // use a constant of two samples for current and previous input value
+      samplesInput.push_back( new FGXMLAutoInput(NULL, 2.0 ) ); 
     }
   } else if (aName == "filter-time" ) {
     TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
@@ -724,116 +772,263 @@ void FGDigitalFilter::update(double dt)
         do_feedback();
     }
 
-    if ( enabled && dt > 0.0 ) {
-        /*
-         * Exponential filter
-         *
-         * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
-         *
-         */
-         if( debug ) cout << "Updating " << get_name()
-                          << " dt " << dt << endl;
-
-        if (filterType == exponential)
-        {
-            double alpha = 1 / ((TfInput.get_value()/dt) + 1);
-            output.push_front(alpha * input[0] + 
-                              (1 - alpha) * output[0]);
-        } 
-        else if (filterType == doubleExponential)
+    if ( !enabled || dt < SGLimitsd::min() ) 
+        return;
+
+    /*
+     * Exponential filter
+     *
+     * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
+     *
+     */
+     if( debug ) cout << "Updating " << get_name()
+                      << " dt " << dt << endl;
+
+    if (filterType == exponential)
+    {
+        double alpha = 1 / ((TfInput.get_value()/dt) + 1);
+        output.push_front(alpha * input[0] + 
+                          (1 - alpha) * output[0]);
+    } 
+    else if (filterType == doubleExponential)
+    {
+        double alpha = 1 / ((TfInput.get_value()/dt) + 1);
+        output.push_front(alpha * alpha * input[0] + 
+                          2 * (1 - alpha) * output[0] -
+                          (1 - alpha) * (1 - alpha) * output[1]);
+    }
+    else if (filterType == movingAverage)
+    {
+        output.push_front(output[0] + 
+                          (input[0] - input.back()) / samplesInput.get_value());
+    }
+    else if (filterType == noiseSpike)
+    {
+        double maxChange = rateOfChangeInput.get_value() * dt;
+
+        if ((output[0] - input[0]) > maxChange)
         {
-            double alpha = 1 / ((TfInput.get_value()/dt) + 1);
-            output.push_front(alpha * alpha * input[0] + 
-                              2 * (1 - alpha) * output[0] -
-                              (1 - alpha) * (1 - alpha) * output[1]);
+            output.push_front(output[0] - maxChange);
         }
-        else if (filterType == movingAverage)
+        else if ((output[0] - input[0]) < -maxChange)
         {
-            output.push_front(output[0] + 
-                              (input[0] - input.back()) / samplesInput.get_value());
+            output.push_front(output[0] + maxChange);
         }
-        else if (filterType == noiseSpike)
+        else if (fabs(input[0] - output[0]) <= maxChange)
         {
-            double maxChange = rateOfChangeInput.get_value() * dt;
-
-            if ((output[0] - input[0]) > maxChange)
-            {
-                output.push_front(output[0] - maxChange);
-            }
-            else if ((output[0] - input[0]) < -maxChange)
-            {
-                output.push_front(output[0] + maxChange);
-            }
-            else if (fabs(input[0] - output[0]) <= maxChange)
-            {
-                output.push_front(input[0]);
-            }
+            output.push_front(input[0]);
         }
-        else if (filterType == gain)
-        {
-            output[0] = gainInput.get_value() * input[0];
+    }
+    else if (filterType == gain)
+    {
+        output[0] = gainInput.get_value() * input[0];
+    }
+    else if (filterType == reciprocal)
+    {
+        if (input[0] != 0.0) {
+            output[0] = gainInput.get_value() / input[0];
         }
-        else if (filterType == reciprocal)
-        {
-            if (input[0] != 0.0) {
-                output[0] = gainInput.get_value() / input[0];
-            }
+    }
+    else if (filterType == differential)
+    {
+        if( dt > SGLimitsd::min() ) {
+            output[0] = (input[0]-input[1]) * TfInput.get_value() / dt;
         }
+    }
 
-        output[0] = clamp(output[0]) ;
-        set_output_value( output[0] );
+    output[0] = clamp(output[0]) ;
+    set_output_value( output[0] );
 
-        output.resize(2);
+    output.resize(2);
 
-        if (debug)
-        {
-            cout << "input:" << input[0] 
-                 << "\toutput:" << output[0] << endl;
-        }
+    if (debug)
+    {
+        cout << "input:" << input[0] 
+             << "\toutput:" << output[0] << endl;
     }
 }
 
-
-FGXMLAutopilot::FGXMLAutopilot() {
+FGXMLAutopilotGroup::FGXMLAutopilotGroup() :
+  SGSubsystemGroup(),
+  average(0.0), // average/filtered prediction
+  v_last(0.0),  // last velocity
+  last_static_pressure(0.0),
+  vel(fgGetNode( "/velocities/airspeed-kt", true )),
+  // Estimate speed in 5,10 seconds
+  lookahead5(fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true )),
+  lookahead10(fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true )),
+  bug(fgGetNode( "/autopilot/settings/heading-bug-deg", true )),
+  mag_hdg(fgGetNode( "/orientation/heading-magnetic-deg", true )),
+  bug_error(fgGetNode( "/autopilot/internal/heading-bug-error-deg", true )),
+  fdm_bug_error(fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true )),
+  target_true(fgGetNode( "/autopilot/settings/true-heading-deg", true )),
+  true_hdg(fgGetNode( "/orientation/heading-deg", true )),
+  true_error(fgGetNode( "/autopilot/internal/true-heading-error-deg", true )),
+  target_nav1(fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true )),
+  true_nav1(fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true )),
+  true_track_nav1(fgGetNode( "/autopilot/internal/nav1-track-error-deg", true )),
+  nav1_course_error(fgGetNode( "/autopilot/internal/nav1-course-error", true )),
+  nav1_selected_course(fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true )),
+  vs_fps(fgGetNode( "/velocities/vertical-speed-fps", true )),
+  vs_fpm(fgGetNode( "/autopilot/internal/vert-speed-fpm", true )),
+  static_pressure(fgGetNode( "/systems/static[0]/pressure-inhg", true )),
+  pressure_rate(fgGetNode( "/autopilot/internal/pressure-rate", true )),
+  track(fgGetNode( "/orientation/track-deg", true ))
+{
 }
 
+void FGXMLAutopilotGroup::update( double dt )
+{
+    // update all configured autopilots
+    SGSubsystemGroup::update( dt );
 
-FGXMLAutopilot::~FGXMLAutopilot() {
+    // update helper values
+    double v = vel->getDoubleValue();
+    double a = 0.0;
+    if ( dt > 0.0 ) {
+        a = (v - v_last) / dt;
+
+        if ( dt < 1.0 ) {
+            average = (1.0 - dt) * average + dt * a;
+        } else {
+            average = a;
+        }
+
+        lookahead5->setDoubleValue( v + average * 5.0 );
+        lookahead10->setDoubleValue( v + average * 10.0 );
+        v_last = v;
+    }
+
+    // Calculate heading bug error normalized to +/- 180.0
+    double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
+    bug_error->setDoubleValue( diff );
+
+    fdm_bug_error->setDoubleValue( diff );
+
+    // Calculate true heading error normalized to +/- 180.0
+    diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
+    true_error->setDoubleValue( diff );
+
+    // Calculate nav1 target heading error normalized to +/- 180.0
+    diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
+    true_nav1->setDoubleValue( diff );
+
+    // Calculate true groundtrack
+    diff = target_nav1->getDoubleValue() - track->getDoubleValue();
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
+    true_track_nav1->setDoubleValue( diff );
+
+    // Calculate nav1 selected course error normalized to +/- 180.0
+    diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
+    SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
+    nav1_course_error->setDoubleValue( diff );
+
+    // Calculate vertical speed in fpm
+    vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
+
+
+    // Calculate static port pressure rate in [inhg/s].
+    // Used to determine vertical speed.
+    if ( dt > 0.0 ) {
+        double current_static_pressure = static_pressure->getDoubleValue();
+        double current_pressure_rate = 
+            ( current_static_pressure - last_static_pressure ) / dt;
+
+        pressure_rate->setDoubleValue(current_pressure_rate);
+        last_static_pressure = current_static_pressure;
+    }
 }
 
-void FGXMLAutopilot::init() {
-    config_props = fgGetNode( "/autopilot/new-config", true );
+void FGXMLAutopilotGroup::reinit()
+{
+    for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
+      FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
+      if( ap == NULL ) continue; // ?
+      remove_subsystem( _autopilotNames[i] );
+      delete ap;
+    }
+    _autopilotNames.clear();
+    init();
+}
 
-    SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
+void FGXMLAutopilotGroup::init()
+{
+    vector<SGPropertyNode_ptr> autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
+    if( autopilotNodes.size() == 0 ) {
+        SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
+        return;
+    }
+
+    for( vector<SGPropertyNode_ptr>::size_type i = 0; i < autopilotNodes.size(); i++ ) {
+        SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
+        if( pathNode == NULL ) {
+            SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
+            continue;
+        }
+
+        string apName;
+        SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
+        if( nameNode != NULL ) {
+            apName = nameNode->getStringValue();
+        } else {
+          std::ostringstream buf;
+          buf <<  "unnamed_autopilot_" << i;
+          apName = buf.str();
+        }
+
+        if( get_subsystem( apName.c_str() ) != NULL ) {
+            SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
+            continue;
+        }
 
-    if ( path_n ) {
         SGPath config( globals->get_fg_root() );
-        config.append( path_n->getStringValue() );
+        config.append( pathNode->getStringValue() );
 
-        SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
-                << config.str() );
+        SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
+        // FGXMLAutopilot
+        FGXMLAutopilot * ap = new FGXMLAutopilot;
         try {
-            readProperties( config.str(), config_props );
+            SGPropertyNode_ptr root = new SGPropertyNode();
+            readProperties( config.str(), root );
 
-            if ( ! build() ) {
-                SG_LOG( SG_ALL, SG_ALERT,
-                        "Detected an internal inconsistency in the autopilot");
-                SG_LOG( SG_ALL, SG_ALERT,
-                        " configuration.  See earlier errors for" );
+
+            if ( ! ap->build( root ) ) {
                 SG_LOG( SG_ALL, SG_ALERT,
-                        " details.");
-                exit(-1);
+                  "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
+                delete ap;
+                continue;
             }        
         } catch (const sg_exception& e) {
-            SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
+            SG_LOG( SG_AUTOPILOT, SG_ALERT, "Failed to load autopilot configuration: "
                     << config.str() << ":" << e.getMessage() );
+            delete ap;
+            continue;
         }
 
-    } else {
-        SG_LOG( SG_ALL, SG_WARN,
-                "No autopilot configuration specified for this model!");
+        SG_LOG( SG_AUTOPILOT, SG_INFO, "adding  autopilot subsystem " << apName );
+        set_subsystem( apName, ap );
+        _autopilotNames.push_back( apName );
     }
+
+    SGSubsystemGroup::init();
+}
+
+FGXMLAutopilot::FGXMLAutopilot() {
+}
+
+
+FGXMLAutopilot::~FGXMLAutopilot() {
+}
+
+/* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
+ * and configure/add the digital filters specified in that file
+ */
+void FGXMLAutopilot::init() 
+{
 }
 
 
@@ -849,7 +1044,7 @@ void FGXMLAutopilot::bind() {
 void FGXMLAutopilot::unbind() {
 }
 
-bool FGXMLAutopilot::build() {
+bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
     SGPropertyNode *node;
     int i;
 
@@ -858,6 +1053,7 @@ bool FGXMLAutopilot::build() {
         node = config_props->getChild(i);
         string name = node->getName();
         // cout << name << endl;
+        SG_LOG( SG_AUTOPILOT, SG_BULK, "adding  autopilot component " << name );
         if ( name == "pid-controller" ) {
             components.push_back( new FGPIDController( node ) );
         } else if ( name == "pi-simple-controller" ) {
@@ -867,159 +1063,20 @@ bool FGXMLAutopilot::build() {
         } else if ( name == "filter" ) {
             components.push_back( new FGDigitalFilter( node ) );
         } else {
-            SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
-                    << name );
-            return false;
+            SG_LOG( SG_AUTOPILOT, SG_WARN, "Unknown top level autopilot section: " << name );
+//            return false;
         }
     }
 
     return true;
 }
 
-
-/*
- * Update helper values
- */
-static void update_helper( double dt ) {
-    // Estimate speed in 5,10 seconds
-    static SGPropertyNode_ptr vel = fgGetNode( "/velocities/airspeed-kt", true );
-    static SGPropertyNode_ptr lookahead5
-        = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
-    static SGPropertyNode_ptr lookahead10
-        = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
-
-    static double average = 0.0; // average/filtered prediction
-    static double v_last = 0.0;  // last velocity
-
-    double v = vel->getDoubleValue();
-    double a = 0.0;
-    if ( dt > 0.0 ) {
-        a = (v - v_last) / dt;
-
-        if ( dt < 1.0 ) {
-            average = (1.0 - dt) * average + dt * a;
-        } else {
-            average = a;
-        }
-
-        lookahead5->setDoubleValue( v + average * 5.0 );
-        lookahead10->setDoubleValue( v + average * 10.0 );
-        v_last = v;
-    }
-
-    // Calculate heading bug error normalized to +/- 180.0 (based on
-    // DG indicated heading)
-    static SGPropertyNode_ptr bug
-        = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
-    static SGPropertyNode_ptr ind_hdg
-        = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
-                     true );
-    static SGPropertyNode_ptr ind_bug_error
-        = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
-
-    double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
-    ind_bug_error->setDoubleValue( diff );
-
-    // Calculate heading bug error normalized to +/- 180.0 (based on
-    // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
-    // compass.)
-    static SGPropertyNode_ptr mag_hdg
-        = fgGetNode( "/orientation/heading-magnetic-deg", true );
-    static SGPropertyNode_ptr fdm_bug_error
-        = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
-
-    diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
-    fdm_bug_error->setDoubleValue( diff );
-
-    // Calculate true heading error normalized to +/- 180.0
-    static SGPropertyNode_ptr target_true
-        = fgGetNode( "/autopilot/settings/true-heading-deg", true );
-    static SGPropertyNode_ptr true_hdg
-        = fgGetNode( "/orientation/heading-deg", true );
-    static SGPropertyNode_ptr true_track
-        = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
-    static SGPropertyNode_ptr true_error
-        = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
-
-    diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
-    true_error->setDoubleValue( diff );
-
-    // Calculate nav1 target heading error normalized to +/- 180.0
-    static SGPropertyNode_ptr target_nav1
-        = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
-    static SGPropertyNode_ptr true_nav1
-        = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
-    static SGPropertyNode_ptr true_track_nav1
-        = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
-
-    diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
-    true_nav1->setDoubleValue( diff );
-
-    diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
-    true_track_nav1->setDoubleValue( diff );
-
-    // Calculate nav1 selected course error normalized to +/- 180.0
-    // (based on DG indicated heading)
-    static SGPropertyNode_ptr nav1_course_error
-        = fgGetNode( "/autopilot/internal/nav1-course-error", true );
-    static SGPropertyNode_ptr nav1_selected_course
-        = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
-
-    diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
-//    if ( diff < -180.0 ) { diff += 360.0; }
-//    if ( diff > 180.0 ) { diff -= 360.0; }
-    SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
-    nav1_course_error->setDoubleValue( diff );
-
-    // Calculate vertical speed in fpm
-    static SGPropertyNode_ptr vs_fps
-        = fgGetNode( "/velocities/vertical-speed-fps", true );
-    static SGPropertyNode_ptr vs_fpm
-        = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
-
-    vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
-
-
-    // Calculate static port pressure rate in [inhg/s].
-    // Used to determine vertical speed.
-    static SGPropertyNode_ptr static_pressure
-       = fgGetNode( "/systems/static[0]/pressure-inhg", true );
-    static SGPropertyNode_ptr pressure_rate
-       = fgGetNode( "/autopilot/internal/pressure-rate", true );
-
-    static double last_static_pressure = 0.0;
-
-    if ( dt > 0.0 ) {
-       double current_static_pressure = static_pressure->getDoubleValue();
-
-       double current_pressure_rate = 
-           ( current_static_pressure - last_static_pressure ) / dt;
-
-       pressure_rate->setDoubleValue(current_pressure_rate);
-
-       last_static_pressure = current_static_pressure;
-    }
-
-}
-
-
 /*
  * Update the list of autopilot components
  */
 
-void FGXMLAutopilot::update( double dt ) {
-    update_helper( dt );
-
+void FGXMLAutopilot::update( double dt ) 
+{
     unsigned int i;
     for ( i = 0; i < components.size(); ++i ) {
         components[i]->update( dt );
index 3f68fb20c31f8283f4e36a5464f8fd91eb12a698..6d7d3f2aaf2478c6c1318ef105d8536990898523 100644 (file)
 #include <simgear/structure/subsystem_mgr.hxx>
 #include <simgear/props/condition.hxx>
 
+typedef SGSharedPtr<class FGXMLAutoInput> FGXMLAutoInput_ptr;
+typedef SGSharedPtr<class FGPeriodicalValue> FGPeriodicalValue_ptr;
+
+class FGPeriodicalValue : public SGReferenced {
+private:
+     FGXMLAutoInput_ptr minPeriod; // The minimum value of the period
+     FGXMLAutoInput_ptr maxPeriod; // The maximum value of the period
+public:
+     FGPeriodicalValue( SGPropertyNode_ptr node );
+     double normalize( double value );
+};
 
 class FGXMLAutoInput : public SGReferenced {
 private:
      double             value;    // The value as a constant or initializer for the property
      bool               abs;      // return absolute value
      SGPropertyNode_ptr property; // The name of the property containing the value
-     SGSharedPtr<FGXMLAutoInput> offset;   // A fixed offset, defaults to zero
-     SGSharedPtr<FGXMLAutoInput> scale;    // A constant scaling factor defaults to one
-     SGSharedPtr<FGXMLAutoInput> min;      // A minimum clip defaults to no clipping
-     SGSharedPtr<FGXMLAutoInput> max;      // A maximum clip defaults to no clipping
+     FGXMLAutoInput_ptr offset;   // A fixed offset, defaults to zero
+     FGXMLAutoInput_ptr scale;    // A constant scaling factor defaults to one
+     FGXMLAutoInput_ptr min;      // A minimum clip defaults to no clipping
+     FGXMLAutoInput_ptr max;      // A maximum clip defaults to no clipping
+     FGPeriodicalValue_ptr  periodical; //
      SGSharedPtr<const SGCondition> _condition;
 
 public:
@@ -71,9 +83,9 @@ public:
 
 };
 
-class FGXMLAutoInputList : public std::vector<SGSharedPtr<FGXMLAutoInput> > {
+class FGXMLAutoInputList : public std::vector<FGXMLAutoInput_ptr> {
   public:
-    FGXMLAutoInput * get_active() {
+    FGXMLAutoInput_ptr get_active() {
       for (iterator it = begin(); it != end(); ++it) {
         if( (*it)->is_enabled() )
           return *it;
@@ -82,7 +94,7 @@ class FGXMLAutoInputList : public std::vector<SGSharedPtr<FGXMLAutoInput> > {
     }
 
     double get_value( double def = 0.0 ) {
-      FGXMLAutoInput * input = get_active();
+      FGXMLAutoInput_ptr input = get_active();
       return input == NULL ? def : input->get_value();
     }
 
@@ -147,6 +159,7 @@ protected:
     FGXMLAutoInputList referenceInput;
     FGXMLAutoInputList uminInput;
     FGXMLAutoInputList umaxInput;
+    FGPeriodicalValue_ptr periodical;
     // debug flag
     bool debug;
     bool enabled;
@@ -221,6 +234,8 @@ public:
     bool isPropertyEnabled();
 };
 
+typedef SGSharedPtr<FGXMLAutoComponent> FGXMLAutoComponent_ptr;
+
 
 /**
  * Roy Ovesen's PID controller
@@ -339,7 +354,7 @@ private:
     std::deque <double> output;
     std::deque <double> input;
     enum filterTypes { exponential, doubleExponential, movingAverage,
-                       noiseSpike, gain, reciprocal, none };
+                       noiseSpike, gain, reciprocal, differential, none };
     filterTypes filterType;
 
 protected:
@@ -357,6 +372,42 @@ public:
  * 
  */
 
+class FGXMLAutopilotGroup : public SGSubsystemGroup
+{
+public:
+    FGXMLAutopilotGroup();
+    void init();
+    void reinit();
+    void update( double dt );
+private:
+    std::vector<std::string> _autopilotNames;
+
+    double average;
+    double v_last;
+    double last_static_pressure;
+
+    SGPropertyNode_ptr vel;
+    SGPropertyNode_ptr lookahead5;
+    SGPropertyNode_ptr lookahead10;
+    SGPropertyNode_ptr bug;
+    SGPropertyNode_ptr mag_hdg;
+    SGPropertyNode_ptr bug_error;
+    SGPropertyNode_ptr fdm_bug_error;
+    SGPropertyNode_ptr target_true;
+    SGPropertyNode_ptr true_hdg;
+    SGPropertyNode_ptr true_error;
+    SGPropertyNode_ptr target_nav1;
+    SGPropertyNode_ptr true_nav1;
+    SGPropertyNode_ptr true_track_nav1;
+    SGPropertyNode_ptr nav1_course_error;
+    SGPropertyNode_ptr nav1_selected_course;
+    SGPropertyNode_ptr vs_fps;
+    SGPropertyNode_ptr vs_fpm;
+    SGPropertyNode_ptr static_pressure;
+    SGPropertyNode_ptr pressure_rate;
+    SGPropertyNode_ptr track;
+};
+
 class FGXMLAutopilot : public SGSubsystem
 {
 
@@ -371,17 +422,15 @@ public:
     void unbind();
     void update( double dt );
 
-    bool build();
 
+    bool build( SGPropertyNode_ptr );
 protected:
-
-    typedef std::vector<SGSharedPtr<FGXMLAutoComponent> > comp_list;
+    typedef std::vector<FGXMLAutoComponent_ptr> comp_list;
 
 private:
-
     bool serviceable;
-    SGPropertyNode_ptr config_props;
     comp_list components;
+    
 };
 
 
index aae7bf22e2cf4dbe655099e600604ff587b80af6..b06a1917bb68e8a4e97a31ada1be75e2d103f75a 100644 (file)
@@ -182,7 +182,7 @@ int readHud( istream &input )
     }
 
 
-    SG_LOG(SG_INPUT, SG_INFO, "Read properties for  " <<
+    SG_LOG(SG_INPUT, SG_DEBUG, "Read properties for  " <<
            root.getStringValue("name"));
 
     if (!root.getNode("depreciated"))
@@ -191,7 +191,7 @@ int readHud( istream &input )
     HUD_deque.erase( HUD_deque.begin(), HUD_deque.end());
 
 
-    SG_LOG(SG_INPUT, SG_INFO, "Reading Hud instruments");
+    SG_LOG(SG_INPUT, SG_DEBUG, "Reading Hud instruments");
 
     const SGPropertyNode * instrument_group = root.getChild("instruments");
     int nInstruments = instrument_group->nChildren();
@@ -203,7 +203,7 @@ int readHud( istream &input )
         SGPath path( globals->get_fg_root() );
         path.append(node->getStringValue("path"));
 
-        SG_LOG(SG_INPUT, SG_INFO, "Reading Instrument "
+        SG_LOG(SG_INPUT, SG_DEBUG, "Reading Instrument "
                << node->getName()
                << " from "
                << path.str());
index 858c3716f9dacedbe41d83b45632508ae74f0bcc..746e9317a5510a471d3c4bae828b2629dd1f63bc 100644 (file)
@@ -56,7 +56,7 @@ hud_card::hud_card(const SGPropertyNode *node) :
     Maj_div(node->getIntValue("major_divs")),          // FIXME dup
     Min_div(node->getIntValue("minor_divs"))           // FIXME dup
 {
-    SG_LOG(SG_INPUT, SG_INFO, "Done reading dial/tape instrument "
+    SG_LOG(SG_INPUT, SG_BULK, "Done reading dial/tape instrument "
             << node->getStringValue("name", "[unnamed]"));
 
     set_data_source(get_func(node->getStringValue("loadfn")));
index 04c2018ed02c2da4045451729856824df122990f..7a4d5ce6fe52a65f373fb56e8539479b8a503672 100644 (file)
@@ -26,7 +26,7 @@ gauge_instr::gauge_instr(const SGPropertyNode *node) :
             0, /* hud.cxx: static int dp_shoing = 0; */    // FIXME
             node->getBoolValue("working", true))
 {
-    SG_LOG(SG_INPUT, SG_INFO, "Done reading gauge instrument "
+    SG_LOG(SG_INPUT, SG_BULK, "Done reading gauge instrument "
             << node->getStringValue("name", "[unnamed]"));
 
     set_data_source(get_func(node->getStringValue("loadfn")));
index d19fed05696da5f33f462dcbf281898f00577699..95d69142a5104e9d7ee76840596edeac82130290 100644 (file)
@@ -33,7 +33,7 @@ instr_label::instr_label(const SGPropertyNode *node) :
     lon_node(fgGetNode("/position/longitude-string", true)),
     lat_node(fgGetNode("/position/latitude-string", true))
 {
-    SG_LOG(SG_INPUT, SG_INFO, "Done reading instr_label instrument "
+    SG_LOG(SG_INPUT, SG_BULK, "Done reading instr_label instrument "
             << node->getStringValue("name", "[unnamed]"));
 
     set_data_source(get_func(node->getStringValue("data_source")));
index 38def8d9d7c85b4c13b1d2d7bc59c0232f46a1e4..34b58d0eb7bf0a5286b1f5ab524a0deee037a193 100644 (file)
@@ -51,7 +51,7 @@ HudLadder::HudLadder(const SGPropertyNode *node) :
     if (fgGetBool("/sim/hud/enable3d", true) && HUD_style == 1)
         factor = 640.0 / 55.0;
 
-    SG_LOG(SG_INPUT, SG_INFO, "Done reading HudLadder instrument"
+    SG_LOG(SG_INPUT, SG_BULK, "Done reading HudLadder instrument"
             << node->getStringValue("name", "[unnamed]"));
 
     if (!width_units)
index 2bc15bcd1fcabc4c5c826efbd3f688d294b7469e..0f7866619ac7607efc9212312b53aa2c12af93c4 100644 (file)
@@ -60,7 +60,7 @@ runway_instr::runway_instr(const SGPropertyNode *node) :
     drawIA(arrowScale > 0 ? true : false),
     drawIAAlways(arrowScale > 0 ? node->getBoolValue("arrow_always") : false)
 {
-    SG_LOG(SG_INPUT, SG_INFO, "Done reading runway instrument "
+    SG_LOG(SG_INPUT, SG_BULK, "Done reading runway instrument "
             << node->getStringValue("name", "[unnamed]"));
 
     view[0] = 0;
index 0c96340d14bd9fe5a73fd87a1dcd70b80d415357..c5fd670c62bc431159d0f33dfe4646b700b225dd 100644 (file)
@@ -32,7 +32,7 @@ fgTBI_instr::fgTBI_instr(const SGPropertyNode *node) :
     rad(node->getFloatValue("rad"))
 
 {
-    SG_LOG(SG_INPUT, SG_INFO, "Done reading TBI instrument"
+    SG_LOG(SG_INPUT, SG_BULK, "Done reading TBI instrument"
             << node->getStringValue("name", "[unnamed]"));
 }
 
index e2caa87f0cc1d0bd963f7d34422e4e2e3dfb389f..be2f12570e8fb3d336e9e79d0c68ccee5b2a0155 100644 (file)
@@ -1109,7 +1109,12 @@ FGTextLayer::draw (osg::State& state)
     transform();
 
     FGFontCache *fc = globals->get_fontcache();
-    text_renderer.setFont(fc->getTexFont(_font_name.c_str()));
+    fntFont* font = fc->getTexFont(_font_name.c_str());
+    if (!font) {
+        return; // don't crash on missing fonts
+    }
+    
+    text_renderer.setFont(font);
 
     text_renderer.setPointSize(_pointSize);
     text_renderer.begin();
@@ -1170,6 +1175,11 @@ void
 FGTextLayer::setFontName(const string &name)
 {
   _font_name = name + ".txf";
+  FGFontCache *fc = globals->get_fontcache();
+  fntFont* font = fc->getTexFont(_font_name.c_str());
+  if (!font) {
+      SG_LOG(SG_GENERAL, SG_WARN, "unable to find font:" << name);
+  }
 }
 
 
index fdb6b26868321f96c723a3e48354e27d33c90bc0..7ef58b6e1522ed393a9e1d2e0a34abeef30b4f41 100644 (file)
@@ -684,7 +684,6 @@ readPanel (const SGPropertyNode * root)
   if (bgTexture.empty())
     bgTexture = "FOO";
   panel->setBackground(FGTextureManager::createTexture(bgTexture.c_str()));
-  SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << bgTexture );
 
   //
   // Get multibackground if any...
@@ -692,49 +691,41 @@ readPanel (const SGPropertyNode * root)
   string mbgTexture = root->getStringValue("multibackground[0]");
   if (!mbgTexture.empty()) {
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 0);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[1]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 1);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[2]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 2);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[3]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 3);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[4]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 4);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[5]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 5);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[6]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 6);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
     mbgTexture = root->getStringValue("multibackground[7]");
     if (mbgTexture.empty())
       mbgTexture = "FOO";
     panel->setMultiBackground(FGTextureManager::createTexture(mbgTexture.c_str()), 7);
-    SG_LOG( SG_COCKPIT, SG_INFO, "Set background texture to " << mbgTexture );
 
   }
   
@@ -743,7 +734,7 @@ readPanel (const SGPropertyNode * root)
   //
   // Create each instrument.
   //
-  SG_LOG( SG_COCKPIT, SG_INFO, "Reading panel instruments" );
+  SG_LOG( SG_COCKPIT, SG_DEBUG, "Reading panel instruments" );
   const SGPropertyNode * instrument_group = root->getChild("instruments");
   if (instrument_group != 0) {
     int nInstruments = instrument_group->nChildren();
@@ -799,12 +790,12 @@ readPanel (const SGPropertyNode * root)
           SG_LOG( SG_COCKPIT, SG_WARN, "Unknown special instrument found" );
         }
       } else {
-        SG_LOG( SG_COCKPIT, SG_INFO, "Skipping " << node->getName()
+        SG_LOG( SG_COCKPIT, SG_WARN, "Skipping " << node->getName()
         << " in instruments section" );
       }
     }
   }
-  SG_LOG( SG_COCKPIT, SG_INFO, "Done reading panel instruments" );
+  SG_LOG( SG_COCKPIT, SG_BULK, "Done reading panel instruments" );
 
 
   //
index ad36f28cf0e664152fceeead119e9e79e6be7356..6fd219bc932ec3bf1b67e63925d35e9af47b1d96 100644 (file)
@@ -88,15 +88,14 @@ void FGACMS::update( double dt ) {
     _set_V_calibrated_kts( kts );
     _set_V_ground_speed( kts );
 
-    SGGeod pos = SGGeod::fromDegM(get_Longitude(), get_Latitude(), get_Altitude());
+    SGGeod pos = getPosition();
     // update (lon/lat) position
     SGGeod pos2;
     double az2;
     geo_direct_wgs_84 ( pos, heading * SGD_RADIANS_TO_DEGREES,
                         dist, pos2, &az2 );
 
-    _set_Longitude( pos2.getLongitudeRad() );
-    _set_Latitude( pos2.getLatitudeRad() );
+    _set_Geodetic_Position(  pos2.getLatitudeRad(), pos2.getLongitudeRad(), pos.getElevationFt() );
 
     double sl_radius, lat_geoc;
     sgGeodToGeoc( get_Latitude(), get_Altitude(), &sl_radius, &lat_geoc );
index 99c937433daa222ee211e92b035045fbaf3fc157..44bffd0ef7e5dd324647fcbfb0c9ae9c32564611 100644 (file)
@@ -93,8 +93,7 @@ void FGMagicCarpet::update( double dt ) {
                            get_Psi() * SGD_RADIANS_TO_DEGREES,
                            dist, &lat2, &lon2, &az2 );
 
-       _set_Longitude( lon2 * SGD_DEGREES_TO_RADIANS );
-       _set_Latitude( lat2 * SGD_DEGREES_TO_RADIANS );
+        _set_Geodetic_Position( lat2 * SGD_DEGREES_TO_RADIANS,  lon2 * SGD_DEGREES_TO_RADIANS );
     }
 
     // cout << "lon error = " << fabs(end.x()*SGD_RADIANS_TO_DEGREES - lon2)
index e8a37fc7b727ebec08d5ceeee34c1512b6c741e2..93928f67d4bdddb30644d51f91137497622d28f8 100644 (file)
@@ -162,8 +162,7 @@ void FGUFO::update( double dt ) {
                             get_Psi() * SGD_RADIANS_TO_DEGREES,
                             dist, &lat2, &lon2, &az2 );
 
-        _set_Longitude( lon2 * SGD_DEGREES_TO_RADIANS );
-        _set_Latitude( lat2 * SGD_DEGREES_TO_RADIANS );
+        _set_Geodetic_Position( lat2 * SGD_DEGREES_TO_RADIANS,  lon2 * SGD_DEGREES_TO_RADIANS );
     }
 
     // cout << "lon error = " << fabs(end.x()*SGD_RADIANS_TO_DEGREES - lon2)
index bc5b3059a2fbeb8ee3ddab07dbe59ed3f7b94104..10ce9948a18722f84d4b596a6726c574d70b5f5a 100644 (file)
@@ -120,6 +120,7 @@ FGInterface::_setup ()
     runway_altitude=0;
     climb_rate=0;
     altitude_agl=0;
+    track=0;
 }
 
 void
@@ -278,6 +279,8 @@ FGInterface::bind ()
        &FGInterface::get_Psi_deg,
        &FGInterface::set_Psi_deg);
   fgSetArchivable("/orientation/heading-deg");
+  fgTie("/orientation/track-deg", this,
+       &FGInterface::get_Track);
 
   // Body-axis "euler rates" (rotation speed, but in a funny
   // representation).
@@ -404,6 +407,7 @@ FGInterface::unbind ()
   fgUntie("/orientation/roll-deg");
   fgUntie("/orientation/pitch-deg");
   fgUntie("/orientation/heading-deg");
+  fgUntie("/orientation/track-deg");
   fgUntie("/orientation/roll-rate-degps");
   fgUntie("/orientation/pitch-rate-degps");
   fgUntie("/orientation/yaw-rate-degps");
@@ -442,6 +446,7 @@ FGInterface::update (double dt)
 
 void FGInterface::_updatePositionM(const SGVec3d& cartPos)
 {
+    TrackComputer tracker( track, geodetic_position_v );
     cartesian_position_v = cartPos;
     geodetic_position_v = SGGeod::fromCart(cartesian_position_v);
     geocentric_position_v = SGGeoc::fromCart(cartesian_position_v);
@@ -452,6 +457,7 @@ void FGInterface::_updatePositionM(const SGVec3d& cartPos)
 
 void FGInterface::_updatePosition(const SGGeod& geod)
 {
+    TrackComputer tracker( track, geodetic_position_v );
     geodetic_position_v = geod;
     cartesian_position_v = SGVec3d::fromGeod(geodetic_position_v);
     geocentric_position_v = SGGeoc::fromCart(cartesian_position_v);
@@ -463,6 +469,7 @@ void FGInterface::_updatePosition(const SGGeod& geod)
 
 void FGInterface::_updatePosition(const SGGeoc& geoc)
 {
+    TrackComputer tracker( track, geodetic_position_v );
     geocentric_position_v = geoc;
     cartesian_position_v = SGVec3d::fromGeoc(geocentric_position_v);
     geodetic_position_v = SGGeod::fromCart(cartesian_position_v);
index ba955145657cda7cb8cbd07253b244d0d4780d89..222df3b546492a29ac427982eda29c3e034f39fa 100644 (file)
@@ -88,6 +88,34 @@ using std::list;
 using std::vector;
 using std::string;
 
+/**
+ * A little helper class to update the track if
+ * the position has changed. In the constructor, 
+ * create a copy of the current position and store 
+ * references to the position object and the track
+ * variable to update.
+ * The destructor, called at TrackComputer's end of 
+ * life/visibility, computes the track if the 
+ * position has changed.
+ */
+class TrackComputer {
+public:
+  inline TrackComputer( double & track, const SGGeod & position ) : 
+    _track( track ),
+    _position( position ),
+    _prevPosition( position ) {
+  }
+
+  inline ~TrackComputer() {
+    if( _prevPosition == _position ) return;
+    _track = SGGeodesy::courseDeg( _prevPosition, _position );
+  }
+private:
+  double & _track;
+  const SGGeod & _position;
+  const SGGeod _prevPosition;
+};
+
 // This is based heavily on LaRCsim/ls_generic.h
 class FGInterface : public SGSubsystem {
 
@@ -157,6 +185,7 @@ private:
     double runway_altitude;
     double climb_rate;                // in feet per second
     double altitude_agl;
+    double track;
 
     double daux[16];           // auxilliary doubles
     float  faux[16];           // auxilliary floats
@@ -265,19 +294,27 @@ public:
        geocentric_position_v.setLongitudeRad(lon);
        geocentric_position_v.setRadiusFt(rad);
     }
+/*  Don't call _set_L[at|ong]itude() directly, use _set_Geodetic_Position() instead.
+    These methods can't update the track.
+ *
     inline void _set_Latitude(double lat) {
         geodetic_position_v.setLatitudeRad(lat);
     }
     inline void _set_Longitude(double lon) {
         geodetic_position_v.setLongitudeRad(lon);
     }
+*/
     inline void _set_Altitude(double altitude) {
         geodetic_position_v.setElevationFt(altitude);
     }
     inline void _set_Altitude_AGL(double agl) {
        altitude_agl = agl;
     }
+    inline void _set_Geodetic_Position( double lat, double lon ) {
+        _set_Geodetic_Position( lat, lon, geodetic_position_v.getElevationFt());
+    }
     inline void _set_Geodetic_Position( double lat, double lon, double alt ) {
+        TrackComputer tracker( track, geodetic_position_v );
        geodetic_position_v.setLatitudeRad(lat);
        geodetic_position_v.setLongitudeRad(lon);
        geodetic_position_v.setElevationFt(alt);
@@ -541,6 +578,7 @@ public:
         return geodetic_position_v.getElevationFt();
     }
     inline double get_Altitude_AGL(void) const { return altitude_agl; }
+    inline double get_Track(void) const { return track; }
 
     inline double get_Latitude_deg () const {
       return geodetic_position_v.getLatitudeDeg();
index 890807f2a9734b5cc12f2d4d673784cbc273d6b6..5f8c98d0bf3539b22e61b90fdd670be5f75a0f40 100644 (file)
@@ -16,14 +16,15 @@ endif
 libGUI_a_SOURCES = \
         new_gui.cxx new_gui.hxx \
         dialog.cxx dialog.hxx \
-       menubar.cxx menubar.hxx \
-       gui.cxx gui.h gui_funcs.cxx \
-       fonts.cxx \
-       AirportList.cxx AirportList.hxx \
+        menubar.cxx menubar.hxx \
+        gui.cxx gui.h gui_funcs.cxx \
+        fonts.cxx \
+        AirportList.cxx AirportList.hxx \
         property_list.cxx property_list.hxx \
         layout.cxx layout-props.cxx layout.hxx \
-       SafeTexFont.cxx SafeTexFont.hxx
-
+        SafeTexFont.cxx SafeTexFont.hxx \
+        WaypointList.cxx WaypointList.hxx
+        
 INCLUDES = -I$(top_srcdir) -I$(top_srcdir)/src
 
 layout_test_SOURCES = layout-test.cxx
diff --git a/src/GUI/WaypointList.cxx b/src/GUI/WaypointList.cxx
new file mode 100644 (file)
index 0000000..5498076
--- /dev/null
@@ -0,0 +1,771 @@
+
+
+#ifdef HAVE_CONFIG_H
+#  include "config.h"
+#endif
+
+#include "WaypointList.hxx"
+
+#include <algorithm>
+#include <plib/puAux.h>
+
+#include <simgear/route/waypoint.hxx>
+#include <simgear/structure/callback.hxx>
+#include <simgear/sg_inlines.h>
+
+#include <Main/globals.hxx>
+#include <Main/fg_props.hxx>
+
+#include <Autopilot/route_mgr.hxx>
+
+enum {
+  SCROLL_NO = 0,
+  SCROLL_UP,
+  SCROLL_DOWN
+};
+  
+static const int DRAG_START_DISTANCE_PX = 5;
+  
+class RouteManagerWaypointModel : 
+  public WaypointList::Model, 
+  public SGPropertyChangeListener
+{
+public:
+  RouteManagerWaypointModel()
+  {
+    _rm = static_cast<FGRouteMgr*>(globals->get_subsystem("route-manager"));
+    
+    SGPropertyNode* routeEdited = fgGetNode("/autopilot/route-manager/signals/edited", true);
+    routeEdited->addChangeListener(this);
+  }
+  
+  virtual ~RouteManagerWaypointModel()
+  {
+    SGPropertyNode* routeEdited = fgGetNode("/autopilot/route-manager/signals/edited", true);
+    routeEdited->removeChangeListener(this);
+  }
+  
+// implement WaypointList::Model
+  virtual unsigned int numWaypoints() const
+  {
+    return _rm->size();
+  }
+  
+  virtual int currentWaypoint() const
+  {
+    return _rm->currentWaypoint();
+  }
+  
+  virtual SGWayPoint waypointAt(unsigned int index) const
+  {
+    return _rm->get_waypoint(index);
+  }
+
+  virtual void deleteAt(unsigned int index)
+  {
+    _rm->pop_waypoint(index);
+  }
+  
+  virtual void setWaypointTargetAltitudeFt(unsigned int index, int altFt)
+  {
+    _rm->setWaypointTargetAltitudeFt(index, altFt);
+  }
+  
+  virtual void moveWaypointToIndex(unsigned int srcIndex, unsigned int destIndex)
+  {
+    if (destIndex > srcIndex) {
+      --destIndex;
+    }
+    
+    SGWayPoint wp = _rm->pop_waypoint(srcIndex);
+    _rm->add_waypoint(wp, destIndex);
+  }
+  
+  virtual void setUpdateCallback(SGCallback* cb)
+  {
+    _cb = cb;
+  }
+    
+// implement SGPropertyChangeListener
+  void valueChanged(SGPropertyNode *prop)
+  {
+    if (_cb) {
+      (*_cb)();
+    }
+  }
+private:
+  FGRouteMgr* _rm;
+  SGCallback* _cb;
+};
+
+//////////////////////////////////////////////////////////////////////////////
+
+static void drawClippedString(puFont& font, const char* s, int x, int y, int maxWidth)
+{
+  int fullWidth = font.getStringWidth(s);
+  if (fullWidth <= maxWidth) { // common case, easy and efficent
+    font.drawString(s, x, y);
+    return;
+  }
+  
+  std::string buf(s);
+  int len = buf.size();
+  do {
+    buf.resize(--len);
+    fullWidth = font.getStringWidth(buf.c_str());
+  } while (fullWidth > maxWidth);
+  
+  font.drawString(buf.c_str(), x, y);
+}
+
+//////////////////////////////////////////////////////////////////////////////
+
+WaypointList::WaypointList(int x, int y, int width, int height) :
+  puFrame(x, y, width, height),
+  GUI_ID(FGCLASS_WAYPOINTLIST),
+  _scrollPx(0),
+  _dragging(false),
+  _dragScroll(SCROLL_NO),
+  _showLatLon(false),
+  _model(NULL),
+  _updateCallback(NULL),
+  _scrollCallback(NULL)
+{
+  // pretend to be a list, so fgPopup doesn't mess with our mouse events
+  type |= PUCLASS_LIST;  
+  setModel(new RouteManagerWaypointModel());
+  setSize(width, height);
+  setValue(-1);
+}
+
+WaypointList::~WaypointList()
+{
+  delete _model;
+  delete _updateCallback;
+  delete _scrollCallback;
+}
+
+void WaypointList::setUpdateCallback(SGCallback* cb)
+{
+  _updateCallback = cb;
+}
+
+void WaypointList::setScrollCallback(SGCallback* cb)
+{
+  _scrollCallback = cb;
+}
+
+void WaypointList::setSize(int width, int height)
+{
+  double scrollP = getVScrollPercent();
+  _heightPx = height;
+  puFrame::setSize(width, height);
+  
+  if (wantsVScroll()) {
+    setVScrollPercent(scrollP);
+  } else {
+    _scrollPx = 0;
+  }
+}
+
+int WaypointList::checkHit ( int button, int updown, int x, int y )
+{
+  if ( isHit( x, y ) || ( puActiveWidget () == this ) )
+  {
+    doHit ( button, updown, x, y ) ;
+    return TRUE ;
+  }
+
+  return FALSE ;
+}
+
+
+void WaypointList::doHit( int button, int updown, int x, int y )
+{
+  puFrame::doHit(button, updown, x, y);  
+  if (updown == PU_DRAG) {
+    handleDrag(x, y);
+    return;
+  }
+  
+  if (button != active_mouse_button) {
+    return;
+  }
+      
+  if (updown == PU_UP) {
+    puDeactivateWidget();
+    if (_dragging) {
+      doDrop(x, y);
+      return;
+    }
+  } else if (updown == PU_DOWN) {
+    puSetActiveWidget(this, x, y);
+    _mouseDownX = x;
+    _mouseDownY = y;
+    return;
+  }
+  
+// update selection
+  int row = rowForY(y - abox.min[1]);
+  if (row >= (int) _model->numWaypoints()) {
+    row = -1; // 'no selection'
+  }
+
+  if (row == getSelected()) {
+    _showLatLon = !_showLatLon;
+    puPostRefresh();
+    return;
+  }
+  
+  setSelected(row);
+}
+
+void WaypointList::handleDrag(int x, int y)
+{
+  if (!_dragging) {
+    // don't start drags immediately, require a certain mouse movement first
+    int manhattanLength = abs(x - _mouseDownX) + abs(y - _mouseDownY);
+    if (manhattanLength < DRAG_START_DISTANCE_PX) {
+      return;
+    }
+    
+    _dragSourceRow = rowForY(y - abox.min[1]);
+    _dragging = true;
+    _dragScroll = SCROLL_NO;
+  }
+  
+  if (y < abox.min[1]) {
+    if (_dragScroll != SCROLL_DOWN) {
+      _dragScroll = SCROLL_DOWN;
+      _dragScrollTime.stamp();
+    }
+  } else if (y > abox.max[1]) {
+    if (_dragScroll != SCROLL_UP) {
+      _dragScroll = SCROLL_UP;
+      _dragScrollTime.stamp();
+    }
+  } else {
+    _dragScroll = SCROLL_NO;
+    _dragTargetRow = rowForY(y - abox.min[1] - (rowHeightPx() / 2));
+  }
+}
+
+void WaypointList::doDrop(int x, int y)
+{
+  _dragging = false;
+  puDeactivateWidget();
+  
+  if ((y < abox.min[1]) || (y >= abox.max[1])) {
+    return;
+  }
+  
+  if (_dragSourceRow != _dragTargetRow) {
+    _model->moveWaypointToIndex(_dragSourceRow, _dragTargetRow);
+    
+    // keep row indexes linged up when moving an item down the list
+    if (_dragSourceRow < _dragTargetRow) {
+      --_dragTargetRow;
+    }
+    
+    setSelected(_dragTargetRow);
+  }
+}
+
+void WaypointList::invokeDownCallback(void)
+{
+  _dragging = false;
+  _dragScroll = SCROLL_NO;
+  SG_LOG(SG_GENERAL, SG_INFO, "cancel drag");
+}
+
+int WaypointList::rowForY(int y) const
+{
+  if (!_model) {
+    return -1;
+  }
+  
+  // flip y to increase down, not up (as rows do)
+  int flipY = _heightPx - y;
+  int row = (flipY + _scrollPx) / rowHeightPx();
+  return row;
+}
+
+void WaypointList::draw( int dx, int dy )
+{
+  puFrame::draw(dx, dy);
+
+  if (!_model) {
+    return;
+  }
+
+  if (_dragScroll != SCROLL_NO) {
+    doDragScroll();
+  }
+  
+  glEnable(GL_SCISSOR_TEST);
+  GLint sx = (int) abox.min[0],
+    sy = abox.min[1];
+  GLsizei w = (GLsizei) abox.max[0] - abox.min[0],
+    h = _heightPx;
+    
+  sx += border_thickness;
+  sy += border_thickness;
+  w -= 2 * border_thickness;
+  h -= 2 * border_thickness;
+    
+  glScissor(sx + dx, sy + dy, w, h);
+  int row = firstVisibleRow(), 
+    final = lastVisibleRow(),
+    rowHeight = rowHeightPx(),
+    y = rowHeight;
+  
+  y -= (_scrollPx % rowHeight); // partially draw the first row
+  
+  for ( ; row <= final; ++row, y += rowHeight) {
+    drawRow(dx, dy, row, y);
+  } // of row drawing iteration
+  
+  glDisable(GL_SCISSOR_TEST);
+    
+  if (_dragging) {
+    // draw the insert marker after the rows
+    int insertY = (_dragTargetRow * rowHeight) - _scrollPx;
+    SG_CLAMP_RANGE(insertY, 0, std::min(_heightPx, totalHeightPx()));
+    
+    glColor4f(1.0f, 0.5f, 0.0f, 0.8f);
+    glLineWidth(3.0f);
+    glBegin(GL_LINES);
+      glVertex2f(dx + abox.min[0], dy + abox.max[1] - insertY);
+      glVertex2f(dx + abox.max[0], dy + abox.max[1] - insertY);
+    glEnd();
+  }
+}
+
+void WaypointList::drawRow(int dx, int dy, int rowIndex, int y)
+{
+  bool isSelected = (rowIndex == getSelected());
+  bool isCurrent = (rowIndex == _model->currentWaypoint());
+  bool isDragSource = (_dragging && (rowIndex == _dragSourceRow));
+  
+  puBox bkgBox = abox;
+  bkgBox.min[1] = abox.max[1] - y;
+  bkgBox.max[1] = bkgBox.min[1] + rowHeightPx();
+  
+  puColour currentColor;
+  puSetColor(currentColor, 1.0, 1.0, 0.0, 0.5);
+  
+  if (isDragSource) {
+    // draw later, on *top* of text string
+  } else  if (isCurrent) {
+    bkgBox.draw(dx, dy, PUSTYLE_PLAIN, &currentColor, false, 0);
+  } else if (isSelected) { // -PLAIN means selected, apparently
+    bkgBox.draw(dx, dy, -PUSTYLE_PLAIN, colour, false, 0);
+  }
+  
+  int xx = dx + abox.min[0] + PUSTR_LGAP;
+  int yy = dy + abox.max[1] - y ;
+  yy += 4; // center text in row height
+  
+  // row textual data
+  const SGWayPoint wp(_model->waypointAt(rowIndex));
+  char buffer[128];
+  int count = ::snprintf(buffer, 128, "%03d   %-5s", rowIndex, wp.get_id().c_str());
+  
+  if (wp.get_name().size() > 0 && (wp.get_name() != wp.get_id())) { 
+    // append name if present, and different to id
+    ::snprintf(buffer + count, 128 - count, " (%s)", wp.get_name().c_str());
+  }
+  
+  glColor4fv ( colour [ PUCOL_LEGEND ] ) ;
+  drawClippedString(legendFont, buffer, xx, yy, 300);
+  
+  if (_showLatLon) {
+    char ns = (wp.get_target_lat() > 0.0) ? 'N' : 'S';
+    char ew = (wp.get_target_lon() > 0.0) ? 'E' : 'W';
+    
+    ::snprintf(buffer, 128 - count, "%4.2f%c %4.2f%c",
+      fabs(wp.get_target_lon()), ew, fabs(wp.get_target_lat()), ns);
+  } else {
+    ::snprintf(buffer, 128 - count, "%03.0f %5.1fnm",
+      wp.get_track(), wp.get_distance() * SG_METER_TO_NM);
+  }
+
+  legendFont.drawString(buffer, xx + 300 + PUSTR_LGAP, yy);
+  
+  int altFt = (int) wp.get_target_alt() * SG_METER_TO_FEET;
+  if (altFt > -9990) {
+    int altHundredFt = (altFt + 50) / 100; // round to nearest 100ft
+    if (altHundredFt < 100) {
+      count = ::snprintf(buffer, 128, "%d'", altHundredFt * 100);
+    } else { // display as a flight-level
+      count = ::snprintf(buffer, 128, "FL%d", altHundredFt);
+    }
+    
+    legendFont.drawString(buffer, xx + 400 + PUSTR_LGAP, yy);
+  } // of valid wp altitude
+  
+  if (isDragSource) {
+    puSetColor(currentColor, 1.0, 0.5, 0.0, 0.5);
+    bkgBox.draw(dx, dy, PUSTYLE_PLAIN, &currentColor, false, 0);
+  }
+}
+
+const double SCROLL_PX_SEC = 200.0;
+
+void WaypointList::doDragScroll()
+{
+  double dt = (SGTimeStamp::now() - _dragScrollTime).toSecs();
+  _dragScrollTime.stamp();
+  int deltaPx = (int)(dt * SCROLL_PX_SEC);
+  
+  if (_dragScroll == SCROLL_UP) {
+    _scrollPx = _scrollPx - deltaPx;
+    SG_CLAMP_RANGE(_scrollPx, 0, scrollRangePx());
+    _dragTargetRow = firstVisibleRow();
+  } else {
+    _scrollPx = _scrollPx + deltaPx;
+    SG_CLAMP_RANGE(_scrollPx, 0, scrollRangePx());
+    _dragTargetRow = lastFullyVisibleRow() + 1;
+  }
+  
+  if (_scrollCallback) {
+    (*_scrollCallback)();
+  }
+}
+
+int WaypointList::getSelected()
+{
+  return getIntegerValue();
+}
+
+void WaypointList::setSelected(int rowIndex)
+{
+  if (rowIndex == getSelected()) {
+    return;
+  }
+  
+  setValue(rowIndex);
+  invokeCallback();
+  if (rowIndex == -1) {
+    return;
+  }
+
+  ensureRowVisible(rowIndex);
+}
+
+void WaypointList::ensureRowVisible(int rowIndex)
+{
+  if ((rowIndex >= firstFullyVisibleRow()) && (rowIndex <= lastFullyVisibleRow())) {
+    return; // already visible, fine
+  }
+  
+  // ideal position would place the desired row in the middle of the
+  // visible section - hence subtract half the visible height.
+  int targetScrollPx = (rowIndex * rowHeightPx()) - (_heightPx / 2);
+  
+  // clamp the scroll value to something valid
+  SG_CLAMP_RANGE(targetScrollPx, 0, scrollRangePx());
+  _scrollPx = targetScrollPx;
+  
+  puPostRefresh();
+  if (_scrollCallback) { // keep scroll observers in sync
+    (*_scrollCallback)();
+  }
+}
+
+unsigned int WaypointList::numWaypoints() const
+{
+  if (!_model) {
+    return 0;
+  }
+  
+  return _model->numWaypoints();
+}
+
+bool WaypointList::wantsVScroll() const
+{
+  return totalHeightPx() > _heightPx;
+}
+
+float WaypointList::getVScrollPercent() const
+{
+  float scrollRange = scrollRangePx();
+  if (scrollRange < 1.0f) {
+    return 0.0;
+  }
+  
+  return _scrollPx / scrollRange;
+}
+
+float WaypointList::getVScrollThumbPercent() const
+{
+  return _heightPx / (float) totalHeightPx();
+}
+
+void WaypointList::setVScrollPercent(float perc)
+{
+  float scrollRange = scrollRangePx();
+  _scrollPx = (int)(scrollRange * perc);
+}
+
+int WaypointList::firstVisibleRow() const
+{
+  return _scrollPx / rowHeightPx();
+}
+
+int WaypointList::firstFullyVisibleRow() const
+{
+  int rh = rowHeightPx();
+  return (_scrollPx + rh - 1) / rh;
+}
+  
+int WaypointList::numVisibleRows() const
+{
+  int rh = rowHeightPx();
+  int topOffset = _scrollPx % rh; // pixels of first visible row
+  return (_heightPx - topOffset + rh - 1) / rh;
+
+}
+
+int WaypointList::numFullyVisibleRows() const
+{
+  int rh = rowHeightPx();
+  int topOffset = _scrollPx % rh; // pixels of first visible row
+  return (_heightPx - topOffset) / rh;
+}
+
+int WaypointList::rowHeightPx() const
+{
+  return legendFont.getStringHeight() + PUSTR_BGAP;
+}
+
+int WaypointList::scrollRangePx() const
+{
+  return std::max(0, totalHeightPx() - _heightPx);
+}
+
+int WaypointList::totalHeightPx() const
+{
+  if (!_model) {
+    return 0;
+  }
+  
+  return (int) _model->numWaypoints() * rowHeightPx();
+}
+
+int WaypointList::lastFullyVisibleRow() const
+{
+  int row = firstFullyVisibleRow() + numFullyVisibleRows();
+  return std::min(row, (int) _model->numWaypoints() - 1);
+}
+
+int WaypointList::lastVisibleRow() const
+{
+  int row = firstVisibleRow() + numVisibleRows();
+  return std::min(row, (int) _model->numWaypoints() - 1);
+}
+
+void WaypointList::setModel(Model* model)
+{
+  if (_model) {
+    delete _model;
+  }
+  
+  _model = model;
+  _model->setUpdateCallback(make_callback(this, &WaypointList::modelUpdateCallback));
+  
+  puPostRefresh();
+}
+
+int WaypointList::checkKey (int key, int updown )
+{
+  if ((updown == PU_UP) || !isVisible () || !isActive () || (window != puGetWindow())) {
+    return FALSE ;
+  }
+  
+  switch (key)
+  {
+  case PU_KEY_HOME:
+    setSelected(0);
+    break;
+
+  case PU_KEY_END:
+    setSelected(_model->numWaypoints() - 1);
+    break ;
+
+  case PU_KEY_UP        :
+  case PU_KEY_PAGE_UP   :
+    if (getSelected() >= 0) {
+      setSelected(getSelected() - 1);
+    }
+    break ;
+
+  case PU_KEY_DOWN      :
+  case PU_KEY_PAGE_DOWN : {
+    int newSel = getSelected() + 1;
+    if (newSel >= (int) _model->numWaypoints()) {
+      setSelected(-1);
+    } else {
+      setSelected(newSel);
+    }
+    break ;
+  }
+  
+  case '-':
+    if (getSelected() >= 0) {
+      int newAlt = wayptAltFtHundreds(getSelected()) - 10;
+      if (newAlt < 0) {
+        _model->setWaypointTargetAltitudeFt(getSelected(), -9999);
+      } else {
+        _model->setWaypointTargetAltitudeFt(getSelected(), newAlt * 100);
+      }
+    }
+    break;
+    
+  case '=':
+    if (getSelected() >= 0) {
+      int newAlt = wayptAltFtHundreds(getSelected()) + 10;
+      if (newAlt < 0) {
+        _model->setWaypointTargetAltitudeFt(getSelected(), 0);
+      } else {
+        _model->setWaypointTargetAltitudeFt(getSelected(), newAlt * 100);
+      }
+    }
+    break;
+  
+  case 0x7f: // delete
+    if (getSelected() >= 0) {
+      int index = getSelected();
+      _model->deleteAt(index);
+      setSelected(index - 1);
+    }
+    break;
+
+  default :
+    return FALSE;
+  }
+
+  return TRUE ;
+}
+
+int WaypointList::wayptAltFtHundreds(int index) const
+{
+  double alt = _model->waypointAt(index).get_target_alt();
+  if (alt < -9990.0) {
+    return -9999;
+  }
+  
+  int altFt = (int) alt * SG_METER_TO_FEET;
+  return (altFt + 50) / 100; // round to nearest 100ft
+}
+
+void WaypointList::modelUpdateCallback()
+{
+  // local stuff
+  
+  if (_updateCallback) {
+    (*_updateCallback)();
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////
+
+
+static void handle_scrollbar(puObject* scrollbar)
+{
+  ScrolledWaypointList* self = (ScrolledWaypointList*)scrollbar->getUserData();
+  self->setScrollPercent(scrollbar->getFloatValue());
+}
+
+static void waypointListCb(puObject* wpl)
+{
+  ScrolledWaypointList* self = (ScrolledWaypointList*)wpl->getUserData();
+  self->setValue(wpl->getIntegerValue());
+  self->invokeCallback();
+}
+
+ScrolledWaypointList::ScrolledWaypointList(int x, int y, int width, int height) :
+  puGroup(x,y),
+  _scrollWidth(16)
+{
+  // ensure our type is compound, so fgPopup::applySize doesn't descend into
+  // us, and try to cast our children's user-data to GUIInfo*.
+  type |= PUCLASS_LIST;
+  
+  init(width, height);
+}
+
+void ScrolledWaypointList::setValue(float v)
+{
+  puGroup::setValue(v);
+  _list->setValue(v);
+}
+
+void ScrolledWaypointList::setValue(int v)
+{
+  puGroup::setValue(v);
+  _list->setValue(v);
+}
+
+void ScrolledWaypointList::init(int w, int h)
+{
+  _list = new WaypointList(0, 0, w, h);
+  _list->setUpdateCallback(make_callback(this, &ScrolledWaypointList::modelUpdated));
+  _hasVScroll = _list->wantsVScroll();
+  _list->setUserData(this);
+  _list->setCallback(waypointListCb);
+  
+  _list->setScrollCallback(make_callback(this, &ScrolledWaypointList::updateScroll));
+  
+  _scrollbar = new puaScrollBar(w - _scrollWidth, 0, h, 
+    1 /*arrow*/, 1 /* vertical */, _scrollWidth);
+  _scrollbar->setMinValue(0.0);
+  _scrollbar->setMaxValue(1.0);
+  _scrollbar->setUserData(this);
+  _scrollbar->setCallback(handle_scrollbar);
+  close(); // close the group
+  
+  setSize(w, h);
+}
+
+void ScrolledWaypointList::modelUpdated()
+{  
+  int w, h;
+  getSize(&w, &h);
+  updateWantsScroll(w, h);
+}
+
+void ScrolledWaypointList::setScrollPercent(float v)
+{
+  // slider's min is the bottom, so invert the value
+  _list->setVScrollPercent(1.0f - v); 
+}
+
+void ScrolledWaypointList::setSize(int w, int h)
+{
+  updateWantsScroll(w, h);
+}
+
+void ScrolledWaypointList::updateWantsScroll(int w, int h)
+{
+  _hasVScroll = _list->wantsVScroll();
+  
+  if (_hasVScroll) {
+    _scrollbar->reveal();
+    _scrollbar->setPosition(w - _scrollWidth, 0);
+    _scrollbar->setSize(_scrollWidth, h);
+    _list->setSize(w - _scrollWidth, h);
+    updateScroll();
+  } else {
+    _scrollbar->hide();
+    _list->setSize(w, h);
+  }
+}
+
+void ScrolledWaypointList::updateScroll()
+{
+ // _scrollbar->setMaxValue(_list->numWaypoints());
+  _scrollbar->setValue(1.0f - _list->getVScrollPercent());
+  _scrollbar->setSliderFraction(_list->getVScrollThumbPercent());
+}
+
diff --git a/src/GUI/WaypointList.hxx b/src/GUI/WaypointList.hxx
new file mode 100644 (file)
index 0000000..165a1da
--- /dev/null
@@ -0,0 +1,171 @@
+/**
+ * WaypointList.hxx - scrolling list of waypoints, with special formatting
+ */
+
+#ifndef GUI_WAYPOINT_LIST_HXX
+#define GUI_WAYPOINT_LIST_HXX
+
+#include <simgear/compiler.h>
+#include <simgear/timing/timestamp.hxx>
+
+#include <plib/pu.h>
+
+#include "dialog.hxx" // for GUI_ID
+
+// forward decls
+class puaScrollBar;
+class SGWayPoint;
+class SGCallback;
+
+class WaypointList : public puFrame, public GUI_ID
+{
+public:
+  WaypointList(int x, int y, int width, int height);
+  virtual ~WaypointList();
+
+  virtual void setSize(int width, int height);
+  virtual int checkHit ( int button, int updown, int x, int y);
+  virtual void doHit( int button, int updown, int x, int y ) ;
+  virtual void draw( int dx, int dy ) ;
+  virtual int checkKey(int key, int updown);
+  virtual void invokeDownCallback (void);
+  
+  void setSelected(int rowIndex);
+  int getSelected();
+  
+  /**
+   * Do we want a vertical scrollbar (or similar)
+   */
+  bool wantsVScroll() const;
+  
+  /**
+   * Get scrollbar position as a percentage of total range.
+   * returns negative number if scrolling is not possible
+   */
+  float getVScrollPercent() const;
+  
+  /**
+   *
+   */
+  void setVScrollPercent(float perc);
+  
+  /**
+   * Get required thumb size as percentage of total height
+   */
+  float getVScrollThumbPercent() const;
+  
+  int numVisibleRows() const;
+  
+  void ensureRowVisible(int row);
+  
+  void setUpdateCallback(SGCallback* cb);
+  void setScrollCallback(SGCallback* cb);
+  
+  /**
+   * Abstract interface for waypoint source
+   */
+  class Model
+  {
+  public:
+    virtual ~Model() { }
+    
+    virtual unsigned int numWaypoints() const = 0;
+    virtual int currentWaypoint() const = 0;
+    virtual SGWayPoint waypointAt(unsigned int index) const = 0;
+  
+  // update notifications
+    virtual void setUpdateCallback(SGCallback* cb) = 0;
+  
+  // editing operations
+    virtual void deleteAt(unsigned int index) = 0;
+    virtual void setWaypointTargetAltitudeFt(unsigned int index, int altFt) = 0;
+    virtual void moveWaypointToIndex(unsigned int srcIndex, unsigned int dstIndex) = 0;
+  };
+  
+  void setModel(Model* model);
+  
+  unsigned int numWaypoints() const;
+protected:
+
+private:
+  void drawRow(int dx, int dy, int rowIndex, int yOrigin);
+
+  void handleDrag(int x, int y);
+  void doDrop(int x, int y);
+  void doDragScroll();
+  
+  /**
+   * Pixel height of a row, including padding
+   */
+  int rowHeightPx() const;
+  
+  /**
+   * model row corresponding to an on-screen y-value
+   */
+  int rowForY(int y) const;
+  
+  /**
+   * reutrn rowheight * total number of rows, i.e the height we'd
+   * need to be to show every row without scrolling
+   */
+  int totalHeightPx() const;
+  
+  /**
+   * Pixel scroll range, based on widget height and number of rows
+   */
+  int scrollRangePx() const;
+  
+  int firstVisibleRow() const;
+  int lastVisibleRow() const;
+
+  int numFullyVisibleRows() const;
+  int firstFullyVisibleRow() const;
+  int lastFullyVisibleRow() const;
+  
+  int wayptAltFtHundreds(int index) const;
+  
+  void modelUpdateCallback();
+  
+  int _scrollPx; // scroll ammount (in pixels)
+  int _heightPx;
+  
+  bool _dragging;
+  int _dragSourceRow;
+  int _dragTargetRow;
+  int _mouseDownX, _mouseDownY;
+  
+  int _dragScroll;
+  SGTimeStamp _dragScrollTime;
+
+  bool _showLatLon;
+  Model* _model;
+  SGCallback* _updateCallback;
+  SGCallback* _scrollCallback;
+};
+
+class ScrolledWaypointList : public puGroup
+{
+public:
+  ScrolledWaypointList(int x, int y, int width, int height);
+  
+  virtual void setSize(int width, int height);
+  
+  void setScrollPercent(float v);
+  
+  virtual void setValue(float v);
+  virtual void setValue(int v);
+private:  
+  void init(int w, int h);
+  
+  void updateScroll();
+  void updateWantsScroll(int w, int h);
+  
+  void modelUpdated();
+  
+  puaScrollBar* _scrollbar;
+  WaypointList* _list;
+  int _scrollWidth;
+  bool _hasVScroll;
+};
+
+#endif // GUI_WAYPOINT_LIST_HXX
index 95fe5f04c1fad5f40f56783fb492facf157f66b0..698268ce92dd16c5da88306ab10be7d7a8dd88d8 100644 (file)
@@ -13,7 +13,7 @@
 #include "AirportList.hxx"
 #include "property_list.hxx"
 #include "layout.hxx"
-
+#include "WaypointList.hxx"
 
 enum format_type { f_INVALID, f_INT, f_LONG, f_FLOAT, f_DOUBLE, f_STRING };
 static const int FORMAT_BUFSIZE = 255;
@@ -295,8 +295,16 @@ int fgPopup::checkHit(int button, int updown, int x, int y)
                 getFirstChild()->setSize(w, h); // dialog background puFrame
             }
         } else {
-            setPosition(x + _dlgX - _startX, y + _dlgY - _startY);
-        }
+            int posX = x + _dlgX - _startX,
+              posY = y + _dlgY - _startY;
+            setPosition(posX, posY);
+            
+            GUIInfo *info = (GUIInfo *)getUserData();
+            if (info && info->node) {
+                info->node->setIntValue("x", posX);
+                info->node->setIntValue("y", posY);
+            }
+        } // re-positioning
 
     } else if (_dragging) {
         fgSetMouseCursor(_start_cursor);
@@ -561,9 +569,14 @@ FGDialog::updateValues (const char *objectName)
     
     puObject *widget = _propertyObjects[i]->object;
     int widgetType = widget->getType();
-    if ((widgetType & PUCLASS_LIST) && (dynamic_cast<GUI_ID *>(widget)->id & FGCLASS_LIST)) {
-      fgList *pl = static_cast<fgList*>(widget);
-      pl->update();
+    if (widgetType & PUCLASS_LIST) {
+      GUI_ID* gui_id = dynamic_cast<GUI_ID *>(widget);
+      if (gui_id && (gui_id->id & FGCLASS_LIST)) {
+        fgList *pl = static_cast<fgList*>(widget);
+        pl->update();
+      } else {
+        copy_to_pui(_propertyObjects[i]->node, widget);
+      }
     } else if (widgetType & PUCLASS_COMBOBOX) {
       fgComboBox* combo = static_cast<fgComboBox*>(widget);
       combo->update();
@@ -865,6 +878,10 @@ FGDialog::makeObject (SGPropertyNode *props, int parentWidth, int parentHeight)
         setupObject(obj, props);
         setColor(obj, props, EDITFIELD);
         return obj;
+    } else if (type == "waypointlist") {
+        ScrolledWaypointList* obj = new ScrolledWaypointList(x, y, width, height);
+        setupObject(obj, props);
+        return obj;
     } else {
         return 0;
     }
index 63aef704b1d2ec3354c7b4261749a2054db43515..e08dbe75ae2c414d3d5edc5b927dda34ea3f2f35 100644 (file)
@@ -22,6 +22,8 @@ using std::vector;
 #define FGCLASS_LIST          0x00000001
 #define FGCLASS_AIRPORTLIST   0x00000002
 #define FGCLASS_PROPERTYLIST  0x00000004
+#define FGCLASS_WAYPOINTLIST  0x00000008
+
 class GUI_ID { public: GUI_ID(int id) : id(id) {} virtual ~GUI_ID() {} int id; };
 
 
index 3cd03bbcc494022e4b02184e63487f91da6b20fa..d34f0fe3a9c1eadf3eb86a57b1fd24a6839c5694 100644 (file)
@@ -258,7 +258,7 @@ FGMenuBar::destroy_menubar ()
                                 // Delete all the character arrays
                                 // we were forced to keep around for
                                 // plib.
-    SG_LOG(SG_GENERAL, SG_INFO, "Deleting char arrays");
+    SG_LOG(SG_GENERAL, SG_BULK, "Deleting char arrays");
     for (i = 0; i < _char_arrays.size(); i++) {
         for (int j = 0; _char_arrays[i][j] != 0; j++)
             free(_char_arrays[i][j]); // added with strdup
@@ -268,20 +268,20 @@ FGMenuBar::destroy_menubar ()
                                 // Delete all the callback arrays
                                 // we were forced to keep around for
                                 // plib.
-    SG_LOG(SG_GENERAL, SG_INFO, "Deleting callback arrays");
+    SG_LOG(SG_GENERAL, SG_BULK, "Deleting callback arrays");
     for (i = 0; i < _callback_arrays.size(); i++)
         delete[] _callback_arrays[i];
 
                                 // Delete all those bindings
-    SG_LOG(SG_GENERAL, SG_INFO, "Deleting bindings");
+    SG_LOG(SG_GENERAL, SG_BULK, "Deleting bindings");
     map<string,vector<SGBinding *> >::iterator it;
     for (it = _bindings.begin(); it != _bindings.end(); it++) {
-        SG_LOG(SG_GENERAL, SG_INFO, "Deleting bindings for " << it->first);
+        SG_LOG(SG_GENERAL, SG_BULK, "Deleting bindings for " << it->first);
         for ( i = 0; i < it->second.size(); i++ )
             delete it->second[i];
     }
 
-    SG_LOG(SG_GENERAL, SG_INFO, "Done.");
+    SG_LOG(SG_GENERAL, SG_BULK, "Done.");
 }
 
 void
index ff9c7ad3c337c370a9ed1d79f66e50589fb83778..b17c0b021d10cd4fd84a5fb0e0ac056be5ea5450 100644 (file)
@@ -14,6 +14,8 @@
 #include <simgear/structure/exception.hxx>
 #include <simgear/props/props_io.hxx>
 
+#include <boost/algorithm/string/case_conv.hpp>
+
 #include <Main/fg_props.hxx>
 
 #include "menubar.hxx"
@@ -468,24 +470,29 @@ inline bool FGFontCache::FntParamsLess::operator()(const FntParams& f1,
 struct FGFontCache::fnt *
 FGFontCache::getfnt(const char *name, float size, float slant)
 {
-    string fontName(name);
+    string fontName = boost::to_lower_copy(string(name));
     FntParams fntParams(fontName, size, slant);
     PuFontMap::iterator i = _puFonts.find(fntParams);
-    if (i != _puFonts.end())
+    if (i != _puFonts.end()) {
+        // found in the puFonts map, all done
         return i->second;
+    }
+    
     // fntTexFont s are all preloaded into the _texFonts map
     TexFontMap::iterator texi = _texFonts.find(fontName);
-    fntTexFont* texfont = 0;
-    puFont* pufont = 0;
+    fntTexFont* texfont = NULL;
+    puFont* pufont = NULL;
     if (texi != _texFonts.end()) {
         texfont = texi->second;
     } else {
+        // check the built-in PUI fonts (in guifonts array)
         const GuiFont* guifont = std::find_if(&guifonts[0], guifontsEnd,
                                               GuiFont::Predicate(name));
         if (guifont != guifontsEnd) {
             pufont = guifont->font;
         }
     }
+    
     fnt* f = new fnt;
     if (pufont) {
         f->pufont = pufont;
@@ -527,16 +534,18 @@ FGFontCache::get(SGPropertyNode *node)
 
 void FGFontCache::init()
 {
-    if (!_initialized) {
-        char *envp = ::getenv("FG_FONTS");
-        if (envp != NULL) {
-            _path.set(envp);
-        } else {
-            _path.set(globals->get_fg_root());
-            _path.append("Fonts");
-        }
-        _initialized = true;
+    if (_initialized) {
+        return;
     }
+    
+    char *envp = ::getenv("FG_FONTS");
+    if (envp != NULL) {
+        _path.set(envp);
+    } else {
+        _path.set(globals->get_fg_root());
+        _path.append("Fonts");
+    }
+    _initialized = true;
 }
 
 SGPath
@@ -552,7 +561,7 @@ FGFontCache::getfntpath(const char *name)
 
     path = SGPath(_path);
     path.append("Helvetica.txf");
-    
+    SG_LOG(SG_GENERAL, SG_WARN, "Unknown font name '" << name << "', defaulting to Helvetica");
     return path;
 }
 
@@ -569,9 +578,11 @@ bool FGFontCache::initializeFonts()
         path.append(dirEntry->d_name);
         if (path.extension() == fontext) {
             fntTexFont* f = new fntTexFont;
-            if (f->load((char *)path.c_str()))
-                _texFonts[string(dirEntry->d_name)] = f;
-            else
+            if (f->load((char *)path.c_str())) {
+                // convert font names in the map to lowercase for matching
+                string fontName = boost::to_lower_copy(string(dirEntry->d_name));
+                _texFonts[fontName] = f;
+            } else
                 delete f;
         }
     }
index c028e17aeee061f7fa61e69cbec76182d5e9acaf..b074e229584c91f34703ac981118de29cb52bfe9 100644 (file)
 #include "kln89_symbols.hxx"
 #include <iostream>
 
+#if ENABLE_ATCDCL
 #include <ATCDCL/ATCProjection.hxx>
+#else
+#include <ATC/atcutils.hxx>
+#endif
+
 #include <Main/fg_props.hxx>
 #include <simgear/math/SGMath.hxx>
 #include <simgear/structure/commands.hxx>
@@ -676,12 +681,17 @@ void KLN89::DrawMap(bool draw_avs) {
        double mapScaleMeters = _mapScale * (_mapScaleUnits == 0 ? SG_NM_TO_METER : 1000);
        
        // TODO - use an aligned projection when either DTK or TK up!
+#if ENABLE_ATCDCL
        FGATCAlignedProjection mapProj(SGGeod::fromRad(_gpsLon, _gpsLat), _mapHeading);
-       
+#else  
+        FGKln89AlignedProjection mapProj(SGGeod::fromRad(_gpsLon, _gpsLat), _mapHeading);
+#endif
        double meter_per_pix = (_mapOrientation == 0 ? mapScaleMeters / 20.0f : mapScaleMeters / 29.0f);
-       
        SGGeod bottomLeft = mapProj.ConvertFromLocal(SGVec3d(gps_max(-57.0 * meter_per_pix, -50000), gps_max((_mapOrientation == 0 ? -20.0 * meter_per_pix : -11.0 * meter_per_pix), -25000), 0.0));
        SGGeod topRight = mapProj.ConvertFromLocal(SGVec3d(gps_min(54.0 * meter_per_pix, 50000), gps_min((_mapOrientation == 0 ? 20.0 * meter_per_pix : 29.0 * meter_per_pix), 25000), 0.0));
+
+
+
        
        // Draw Airport labels first (but not one's that are waypoints)
        // Draw Airports first (but not one's that are waypoints)
index 4bfe15d48f9fc9071740c3471934c3d671d52dfc..60eb08856459bc3f6ef8ac02cc4ead3875bb81d6 100644 (file)
@@ -376,6 +376,8 @@ void FGNavRadio::clearOutputs()
   gs_deflection_deg_node->setDoubleValue(0.0);
   gs_deflection_norm_node->setDoubleValue(0.0);
   gs_inrange_node->setBoolValue( false );
+  loc_node->setBoolValue( false );
+  has_gs_node->setBoolValue(false);
   
   to_flag_node->setBoolValue( false );
   from_flag_node->setBoolValue( false );
@@ -925,7 +927,9 @@ void FGNavRadio::search()
     _gs = NULL;
     _dme = NULL;
     nav_id_node->setStringValue("");
-
+    loc_node->setBoolValue(false);
+    has_gs_node->setBoolValue(false);
+    
     _sgr->remove( nav_fx_name );
     _sgr->remove( dme_fx_name );
   }
index b4e2d592e6e7fc0cf4a04376c0b693092ea47f72..e0798d6d421c692834f9cec2e4d710e7366b5556 100644 (file)
@@ -9,6 +9,13 @@ else
 SP_FDM_LIBS = 
 endif
 
+if ENABLE_ATCDCL
+ATCDCL_LIBS = $(top_builddir)/src/ATCDCL/libATCDCL.a
+else
+ATCDCL_LIBS = 
+endif
+
+
 if WITH_EVENTINPUT
 EVENT_LIBS = $(eventinput_LIBS)
 else
@@ -76,7 +83,7 @@ fgfs_SOURCES = bootstrap.cxx
 fgfs_LDADD = \
        libMain.a \
        $(top_builddir)/src/Aircraft/libAircraft.a \
-       $(top_builddir)/src/ATCDCL/libATCDCL.a \
+       $(ATCDCL_LIBS) \
        $(top_builddir)/src/Cockpit/libCockpit.a \
        $(top_builddir)/src/Cockpit/built_in/libBuilt_in.a \
        $(top_builddir)/src/FDM/libFlight.a \
index c8b938473cd1218e06d305653c4166051fa0d0fd..70ceb23b5fd3d2326c18c6fe4c9258461fdf57b7 100644 (file)
@@ -1596,9 +1596,9 @@ static struct {
 void
 fgInitCommands ()
 {
-  SG_LOG(SG_GENERAL, SG_INFO, "Initializing basic built-in commands:");
+  SG_LOG(SG_GENERAL, SG_BULK, "Initializing basic built-in commands:");
   for (int i = 0; built_ins[i].name != 0; i++) {
-    SG_LOG(SG_GENERAL, SG_INFO, "  " << built_ins[i].name);
+    SG_LOG(SG_GENERAL, SG_BULK, "  " << built_ins[i].name);
     globals->get_commands()->addCommand(built_ins[i].name,
                                        built_ins[i].command);
   }
index 27a0311c37ebb0a5b906299a01e5d92d216c825b..bddcc69f1d00c2c3f8410336a057d577a1a9e5f2 100644 (file)
 #include <Airports/dynamics.hxx>
 
 #include <AIModel/AIManager.hxx>
-#include <ATCDCL/ATCmgr.hxx>
-#include <ATCDCL/AIMgr.hxx>
+
+#if ENABLE_ATCDCL
+#   include <ATCDCL/ATCmgr.hxx>
+#   include <ATCDCL/AIMgr.hxx>
+#   include "ATCDCL/commlist.hxx"
+#else
+#   include "ATC/atcutils.hxx"
+#endif
+
 #include <Autopilot/route_mgr.hxx>
 #include <Autopilot/xmlauto.hxx>
 #include <Autopilot/autobrake.hxx>
@@ -82,7 +89,8 @@
 #include <Cockpit/cockpit.hxx>
 #include <Cockpit/panel.hxx>
 #include <Cockpit/panel_io.hxx>
-#ifdef ENABLE_SP_FDM
+
+#if ENABLE_SP_FDM
 #include <FDM/SP/ADA.hxx>
 #include <FDM/SP/ACMS.hxx>
 #include <FDM/SP/MagicCarpet.hxx>
 #include "renderer.hxx"
 #include "viewmgr.hxx"
 #include "main.hxx"
-#include "ATCDCL/commlist.hxx"
+
 
 #ifdef __APPLE__
 #  include <CoreFoundation/CoreFoundation.h>
@@ -974,6 +982,9 @@ fgInitNav ()
 
 // Initialise the frequency search map BEFORE reading
 // the airport database:
+
+
+
     current_commlist = new FGCommList;
     current_commlist->init( globals->get_fg_root() );
     fgAirportDBLoad( aptdb.str(), current_commlist, p_metar.str() );
@@ -1536,7 +1547,7 @@ bool fgInitSubsystems() {
     // Initialize the XML Autopilot subsystem.
     ////////////////////////////////////////////////////////////////////
 
-    globals->add_subsystem( "xml-autopilot", new FGXMLAutopilot );
+    globals->add_subsystem( "xml-autopilot", new FGXMLAutopilotGroup );
     globals->add_subsystem( "route-manager", new FGRouteMgr );
     globals->add_subsystem( "autobrake", new FGAutoBrake );
     
@@ -1596,10 +1607,11 @@ bool fgInitSubsystems() {
     // Initialise the ATC Manager 
     ////////////////////////////////////////////////////////////////////
 
+#if ENABLE_ATCDCL
     SG_LOG(SG_GENERAL, SG_INFO, "  ATC Manager");
     globals->set_ATC_mgr(new FGATCMgr);
     globals->get_ATC_mgr()->init(); 
-    
+
     ////////////////////////////////////////////////////////////////////
     // Initialise the AI Manager 
     ////////////////////////////////////////////////////////////////////
@@ -1607,7 +1619,7 @@ bool fgInitSubsystems() {
     SG_LOG(SG_GENERAL, SG_INFO, "  AI Manager");
     globals->set_AI_mgr(new FGAIMgr);
     globals->get_AI_mgr()->init();
-
+#endif
     ////////////////////////////////////////////////////////////////////
     // Initialise the AI Model Manager
     ////////////////////////////////////////////////////////////////////
index 31f4ae0dac7f5403c1d706349c7ba24d51ff7293..a5726b79b00b7e7ad44d76565dc0acf9e971b9ca 100644 (file)
@@ -355,6 +355,18 @@ getHeadingMag ()
   return magheading;
 }
 
+/**
+ * Return the current track in degrees.
+ */
+static double
+getTrackMag ()
+{
+  double magtrack;
+  magtrack = current_aircraft.fdm_state->get_Track() - getMagVar();
+  if (magtrack < 0) magtrack += 360;
+  return magtrack;
+}
+
 static long
 getWarp ()
 {
@@ -514,6 +526,7 @@ FGProperties::bind ()
 
                                // Orientation
   fgTie("/orientation/heading-magnetic-deg", getHeadingMag);
+  fgTie("/orientation/track-magnetic-deg", getTrackMag);
 
   fgTie("/environment/magnetic-variation-deg", getMagVar);
   fgTie("/environment/magnetic-dip-deg", getMagDip);
@@ -543,6 +556,7 @@ FGProperties::unbind ()
 
                                // Orientation
   fgUntie("/orientation/heading-magnetic-deg");
+  fgUntie("/orientation/track-magnetic-deg");
 
                                // Environment
   fgUntie("/environment/magnetic-variation-deg");
index 178419eb064efa6da3bc520000cf51b19c288cd3..39b081ac151c84d4530f78af7f9d545778c94321 100644 (file)
@@ -1,9 +1,16 @@
+if ENABLE_ATCDCL
+ATCDCL_DIR = ATCDCL
+else
+ATCDCL_DIR = 
+endif
+
+
 SUBDIRS = \
         Include \
         Aircraft \
         Airports \
        ATC \
-        ATCDCL \
+        $(ATCDCL_DIR) \
         Autopilot \
         Cockpit \
         Environment \
index 1f183fec5e438cff82fa7a2efc12176b1e4cb7a8..fc0f16d47614e1521f5b0e7599918d38063b700f 100644 (file)
@@ -1,4 +1,4 @@
-DIST_SUBDIRS = GPSsmooth TerraSync Modeller js_server fgadmin xmlgrep propmerge
+DIST_SUBDIRS = GPSsmooth TerraSync Modeller js_server fgadmin xmlgrep propmerge fgviewer
 
 SUBDIRS = GPSsmooth TerraSync Modeller js_server propmerge fgviewer