]> git.mxchange.org Git - flightgear.git/commitdiff
Autopilot cleanup:
authordavid <david>
Wed, 13 Mar 2002 16:31:21 +0000 (16:31 +0000)
committerdavid <david>
Wed, 13 Mar 2002 16:31:21 +0000 (16:31 +0000)
- implement the standard FGSubsystem interface, for consistency
- eliminate current_autopilot and add get/set_autopilot to FGGlobals,
  for consistency
- use private methods rather than static functions for tying
  properties

There should be no change in functionality.

src/Autopilot/auto_gui.cxx
src/Autopilot/newauto.cxx
src/Autopilot/newauto.hxx
src/Cockpit/hud.cxx
src/GUI/mouse.cxx
src/Input/input.cxx
src/Main/fg_init.cxx
src/Main/globals.hxx
src/Main/main.cxx

index 280cffb0f8aedd30675a0dcda83ef525389569ce..585689094404783120a49ed808b4b347bde763e3 100644 (file)
@@ -206,10 +206,10 @@ void ApHeadingDialog_OK (puObject *me)
        double NewHeading;
        if( scan_number( c, &NewHeading ) )
            {
-               if ( !current_autopilot->get_HeadingEnabled() ) {
-                   current_autopilot->set_HeadingEnabled( true );
+               if ( !globals->get_autopilot()->get_HeadingEnabled() ) {
+                   globals->get_autopilot()->set_HeadingEnabled( true );
                }
-               current_autopilot->HeadingSet( NewHeading );
+               globals->get_autopilot()->HeadingSet( NewHeading );
            } else {
                error = 1;
                s = c;
@@ -224,7 +224,7 @@ void NewHeading(puObject *cb)
 {
     // string ApHeadingLabel( "Enter New Heading" );
     // ApHeadingDialogMessage  -> setLabel(ApHeadingLabel.c_str());
-    float heading = current_autopilot->get_DGTargetHeading();
+    float heading = globals->get_autopilot()->get_DGTargetHeading();
     while ( heading < 0.0 ) { heading += 360.0; }
     ApHeadingDialogInput   ->    setValue ( heading );
     ApHeadingDialogInput    -> acceptInput();
@@ -283,10 +283,10 @@ void ApAltitudeDialog_OK (puObject *me)
        double NewAltitude;
        if( scan_number( c, &NewAltitude) )
            {
-               if ( !current_autopilot->get_AltitudeEnabled() ) {
-                   current_autopilot->set_AltitudeEnabled( true );
+               if ( !globals->get_autopilot()->get_AltitudeEnabled() ) {
+                   globals->get_autopilot()->set_AltitudeEnabled( true );
                }
-               current_autopilot->AltitudeSet( NewAltitude );
+               globals->get_autopilot()->AltitudeSet( NewAltitude );
            } else {
                error = 1;
                s = c;
@@ -299,7 +299,7 @@ void ApAltitudeDialog_OK (puObject *me)
 
 void NewAltitude(puObject *cb)
 {
-    float altitude = current_autopilot->get_TargetAltitude() * SG_METER_TO_FEET;
+    float altitude = globals->get_autopilot()->get_TargetAltitude() * SG_METER_TO_FEET;
     ApAltitudeDialogInput -> setValue( altitude );
     ApAltitudeDialogInput -> acceptInput();
     FG_PUSH_PUI_DIALOG( ApAltitudeDialog );
@@ -359,8 +359,8 @@ static void maxroll_adj( puObject *hs ) {
     hs-> getValue ( &val ) ;
     SG_CLAMP_RANGE ( val, 0.1f, 1.0f ) ;
     //    printf ( "maxroll_adj( %p ) %f %f\n", hs, val, MaxRollAdjust * val ) ;
-    current_autopilot->set_MaxRoll( MaxRollAdjust * val );
-    sprintf( SliderText[ 0 ], "%05.2f", current_autopilot->get_MaxRoll() );
+    globals->get_autopilot()->set_MaxRoll( MaxRollAdjust * val );
+    sprintf( SliderText[ 0 ], "%05.2f", globals->get_autopilot()->get_MaxRoll() );
     APAdjustMaxRollText -> setLabel ( SliderText[ 0 ] ) ;
 }
 
@@ -370,8 +370,8 @@ static void rollout_adj( puObject *hs ) {
     hs-> getValue ( &val ) ;
     SG_CLAMP_RANGE ( val, 0.1f, 1.0f ) ;
     //    printf ( "rollout_adj( %p ) %f %f\n", hs, val, RollOutAdjust * val ) ;
-    current_autopilot->set_RollOut( RollOutAdjust * val );
-    sprintf( SliderText[ 1 ], "%05.2f", current_autopilot->get_RollOut() );
+    globals->get_autopilot()->set_RollOut( RollOutAdjust * val );
+    sprintf( SliderText[ 1 ], "%05.2f", globals->get_autopilot()->get_RollOut() );
     APAdjustRollOutText -> setLabel ( SliderText[ 1 ] );
 }
 
@@ -381,8 +381,8 @@ static void maxaileron_adj( puObject *hs ) {
     hs-> getValue ( &val ) ;
     SG_CLAMP_RANGE ( val, 0.1f, 1.0f ) ;
     //    printf ( "maxaileron_adj( %p ) %f %f\n", hs, val, MaxAileronAdjust * val ) ;
-    current_autopilot->set_MaxAileron( MaxAileronAdjust * val );
-    sprintf( SliderText[ 3 ], "%05.2f", current_autopilot->get_MaxAileron() );
+    globals->get_autopilot()->set_MaxAileron( MaxAileronAdjust * val );
+    sprintf( SliderText[ 3 ], "%05.2f", globals->get_autopilot()->get_MaxAileron() );
     APAdjustMaxAileronText -> setLabel ( SliderText[ 3 ] );
 }
 
@@ -392,8 +392,8 @@ static void rolloutsmooth_adj( puObject *hs ) {
     hs -> getValue ( &val ) ;
     SG_CLAMP_RANGE ( val, 0.1f, 1.0f ) ;
     //    printf ( "rolloutsmooth_adj( %p ) %f %f\n", hs, val, RollOutSmoothAdjust * val ) ;
-    current_autopilot->set_RollOutSmooth( RollOutSmoothAdjust * val );
-    sprintf( SliderText[ 2 ], "%5.2f", current_autopilot->get_RollOutSmooth() );
+    globals->get_autopilot()->set_RollOutSmooth( RollOutSmoothAdjust * val );
+    sprintf( SliderText[ 2 ], "%5.2f", globals->get_autopilot()->get_RollOutSmooth() );
     APAdjustRollOutSmoothText-> setLabel ( SliderText[ 2 ] );
 
 }
@@ -404,19 +404,19 @@ static void goAwayAPAdjust (puObject *)
 }
 
 void cancelAPAdjust( puObject *self ) {
-    current_autopilot->set_MaxRoll( TmpMaxRollValue );
-    current_autopilot->set_RollOut( TmpRollOutValue );
-    current_autopilot->set_MaxAileron( TmpMaxAileronValue );
-    current_autopilot->set_RollOutSmooth( TmpRollOutSmoothValue );
+    globals->get_autopilot()->set_MaxRoll( TmpMaxRollValue );
+    globals->get_autopilot()->set_RollOut( TmpRollOutValue );
+    globals->get_autopilot()->set_MaxAileron( TmpMaxAileronValue );
+    globals->get_autopilot()->set_RollOutSmooth( TmpRollOutSmoothValue );
 
     goAwayAPAdjust(self);
 }
 
 void resetAPAdjust( puObject *self ) {
-    current_autopilot->set_MaxRoll( MaxRollAdjust / 2 );
-    current_autopilot->set_RollOut( RollOutAdjust / 2 );
-    current_autopilot->set_MaxAileron( MaxAileronAdjust / 2 );
-    current_autopilot->set_RollOutSmooth( RollOutSmoothAdjust / 2 );
+    globals->get_autopilot()->set_MaxRoll( MaxRollAdjust / 2 );
+    globals->get_autopilot()->set_RollOut( RollOutAdjust / 2 );
+    globals->get_autopilot()->set_MaxAileron( MaxAileronAdjust / 2 );
+    globals->get_autopilot()->set_RollOutSmooth( RollOutSmoothAdjust / 2 );
 
     FG_POP_PUI_DIALOG( APAdjustDialog );
 
@@ -424,15 +424,15 @@ void resetAPAdjust( puObject *self ) {
 }
 
 void fgAPAdjust( puObject *self ) {
-    TmpMaxRollValue       = current_autopilot->get_MaxRoll();
-    TmpRollOutValue       = current_autopilot->get_RollOut();
-    TmpMaxAileronValue    = current_autopilot->get_MaxAileron();
-    TmpRollOutSmoothValue = current_autopilot->get_RollOutSmooth();
-
-    MaxRollValue       = current_autopilot->get_MaxRoll() / MaxRollAdjust;
-    RollOutValue       = current_autopilot->get_RollOut() / RollOutAdjust;
-    MaxAileronValue    = current_autopilot->get_MaxAileron() / MaxAileronAdjust;
-    RollOutSmoothValue = current_autopilot->get_RollOutSmooth()
+    TmpMaxRollValue       = globals->get_autopilot()->get_MaxRoll();
+    TmpRollOutValue       = globals->get_autopilot()->get_RollOut();
+    TmpMaxAileronValue    = globals->get_autopilot()->get_MaxAileron();
+    TmpRollOutSmoothValue = globals->get_autopilot()->get_RollOutSmooth();
+
+    MaxRollValue       = globals->get_autopilot()->get_MaxRoll() / MaxRollAdjust;
+    RollOutValue       = globals->get_autopilot()->get_RollOut() / RollOutAdjust;
+    MaxAileronValue    = globals->get_autopilot()->get_MaxAileron() / MaxAileronAdjust;
+    RollOutSmoothValue = globals->get_autopilot()->get_RollOutSmooth()
        / RollOutSmoothAdjust;
 
     APAdjustHS0-> setValue ( MaxRollValue ) ;
@@ -468,20 +468,20 @@ void fgAPAdjustInit() {
     int slider_value_x = 160;
     float slider_delta = 0.1f;
 
-    TmpMaxRollValue       = current_autopilot->get_MaxRoll();
-    TmpRollOutValue       = current_autopilot->get_RollOut();
-    TmpMaxAileronValue    = current_autopilot->get_MaxAileron();
-    TmpRollOutSmoothValue = current_autopilot->get_RollOutSmooth();
+    TmpMaxRollValue       = globals->get_autopilot()->get_MaxRoll();
+    TmpRollOutValue       = globals->get_autopilot()->get_RollOut();
+    TmpMaxAileronValue    = globals->get_autopilot()->get_MaxAileron();
+    TmpRollOutSmoothValue = globals->get_autopilot()->get_RollOutSmooth();
 
-    MaxRollAdjust = 2 * current_autopilot->get_MaxRoll();
-    RollOutAdjust = 2 * current_autopilot->get_RollOut();
-    MaxAileronAdjust = 2 * current_autopilot->get_MaxAileron();
-    RollOutSmoothAdjust = 2 * current_autopilot->get_RollOutSmooth();
+    MaxRollAdjust = 2 * globals->get_autopilot()->get_MaxRoll();
+    RollOutAdjust = 2 * globals->get_autopilot()->get_RollOut();
+    MaxAileronAdjust = 2 * globals->get_autopilot()->get_MaxAileron();
+    RollOutSmoothAdjust = 2 * globals->get_autopilot()->get_RollOutSmooth();
 
-    MaxRollValue       = current_autopilot->get_MaxRoll() / MaxRollAdjust;
-    RollOutValue       = current_autopilot->get_RollOut() / RollOutAdjust;
-    MaxAileronValue    = current_autopilot->get_MaxAileron() / MaxAileronAdjust;
-    RollOutSmoothValue = current_autopilot->get_RollOutSmooth()
+    MaxRollValue       = globals->get_autopilot()->get_MaxRoll() / MaxRollAdjust;
+    RollOutValue       = globals->get_autopilot()->get_RollOut() / RollOutAdjust;
+    MaxAileronValue    = globals->get_autopilot()->get_MaxAileron() / MaxAileronAdjust;
+    RollOutSmoothValue = globals->get_autopilot()->get_RollOutSmooth()
        / RollOutSmoothAdjust;
 
     puGetDefaultFonts (  &APAdjustLegendFont,  &APAdjustLabelFont );
@@ -508,7 +508,7 @@ void fgAPAdjustInit() {
        APAdjustHS0-> setCBMode ( PUSLIDER_DELTA ) ;
        APAdjustHS0-> setCallback ( maxroll_adj ) ;
 
-       sprintf( SliderText[ 0 ], "%05.2f", current_autopilot->get_MaxRoll() );
+       sprintf( SliderText[ 0 ], "%05.2f", globals->get_autopilot()->get_MaxRoll() );
        APAdjustMaxRollTitle = new puText ( slider_title_x, slider_y ) ;
        APAdjustMaxRollTitle-> setDefaultValue ( "MaxRoll" ) ;
        APAdjustMaxRollTitle-> getDefaultValue ( &s ) ;
@@ -525,7 +525,7 @@ void fgAPAdjustInit() {
        APAdjustHS1-> setCBMode ( PUSLIDER_DELTA ) ;
        APAdjustHS1-> setCallback ( rollout_adj ) ;
 
-       sprintf( SliderText[ 1 ], "%05.2f", current_autopilot->get_RollOut() );
+       sprintf( SliderText[ 1 ], "%05.2f", globals->get_autopilot()->get_RollOut() );
        APAdjustRollOutTitle = new puText ( slider_title_x, slider_y ) ;
        APAdjustRollOutTitle-> setDefaultValue ( "AdjustRollOut" ) ;
        APAdjustRollOutTitle-> getDefaultValue ( &s ) ;
@@ -543,7 +543,7 @@ void fgAPAdjustInit() {
        APAdjustHS2-> setCallback ( rolloutsmooth_adj ) ;
 
        sprintf( SliderText[ 2 ], "%5.2f", 
-                current_autopilot->get_RollOutSmooth() );
+                globals->get_autopilot()->get_RollOutSmooth() );
        APAdjustRollOutSmoothTitle = new puText ( slider_title_x, slider_y ) ;
        APAdjustRollOutSmoothTitle-> setDefaultValue ( "RollOutSmooth" ) ;
        APAdjustRollOutSmoothTitle-> getDefaultValue ( &s ) ;
@@ -561,7 +561,7 @@ void fgAPAdjustInit() {
        APAdjustHS3-> setCallback ( maxaileron_adj ) ;
 
        sprintf( SliderText[ 3 ], "%05.2f", 
-                current_autopilot->get_MaxAileron() );
+                globals->get_autopilot()->get_MaxAileron() );
        APAdjustMaxAileronTitle = new puText ( slider_title_x, slider_y ) ;
        APAdjustMaxAileronTitle-> setDefaultValue ( "MaxAileron" ) ;
        APAdjustMaxAileronTitle-> getDefaultValue ( &s ) ;
@@ -636,8 +636,8 @@ void TgtAptDialog_OK (puObject *)
         globals->get_route()->add_waypoint( wp );
 
          /* and turn on the autopilot */
-         current_autopilot->set_HeadingEnabled( true );
-         current_autopilot->set_HeadingMode( FGAutopilot::FG_HEADING_WAYPOINT );
+         globals->get_autopilot()->set_HeadingEnabled( true );
+         globals->get_autopilot()->set_HeadingMode( FGAutopilot::FG_HEADING_WAYPOINT );
 
     } else if ( current_fixlist->query( TgtAptId, 0.0, 0.0, 0.0,
                                        &f, &t1, &t2 ) )
@@ -652,8 +652,8 @@ void TgtAptDialog_OK (puObject *)
         globals->get_route()->add_waypoint( wp );
 
          /* and turn on the autopilot */
-         current_autopilot->set_HeadingEnabled( true );
-         current_autopilot->set_HeadingMode( FGAutopilot::FG_HEADING_WAYPOINT );
+         globals->get_autopilot()->set_HeadingEnabled( true );
+         globals->get_autopilot()->set_HeadingMode( FGAutopilot::FG_HEADING_WAYPOINT );
     } else {
        TgtAptId  += " not in database.";
        mkDialog(TgtAptId.c_str());
@@ -755,13 +755,13 @@ void PopWayPoint(puObject *cb)
     // see if there are more waypoints on the list
     if ( globals->get_route()->size() ) {
        // more waypoints
-       current_autopilot->set_HeadingMode( FGAutopilot::FG_HEADING_WAYPOINT );
+       globals->get_autopilot()->set_HeadingMode( FGAutopilot::FG_HEADING_WAYPOINT );
     } else {
        // end of the line
-       current_autopilot->set_HeadingMode( FGAutopilot::FG_TC_HEADING_LOCK );
+       globals->get_autopilot()->set_HeadingMode( FGAutopilot::FG_TC_HEADING_LOCK );
 
        // use current heading
-       current_autopilot
+       globals->get_autopilot()
             ->set_TargetHeading(fgGetDouble("/orientation/heading-deg"));
     }
 }
index eaf69cdf7b6f25a3b461a74d494de83c891b6e70..fb9a37814f4f9b5ffb5b04b751c6c542cca47732 100644 (file)
@@ -45,9 +45,6 @@
 #include "newauto.hxx"
 
 
-FGAutopilot *current_autopilot;
-
-
 /// These statics will eventually go into the class
 /// they are just here while I am experimenting -- NHV :-)
 // AutoPilot Gain Adjuster members
@@ -148,12 +145,6 @@ void FGAutopilot::MakeTargetWPStr( double distance ) {
        sprintf( TargetWP1Str, "%s %.2f NM  ETA %d:%02d",
                 wp1.get_id().c_str(),
                 accum*SG_METER_TO_NM, major, minor );
-       // cout << "distance = " << distance*SG_METER_TO_NM
-       //      << "  gndsp = " << get_ground_speed() 
-       //      << "  time = " << eta
-       //      << "  major = " << major
-       //      << "  minor = " << minor
-       //      << endl;
     }
 
     // next route
@@ -208,44 +199,10 @@ void FGAutopilot::update_old_control_values() {
 
 
 // Initialize autopilot subsystem
-void FGAutopilot::init() {
-    SG_LOG( SG_AUTOPILOT, SG_INFO, "Init AutoPilot Subsystem" );
-
-    // Autopilot control property static get/set bindings
-    fgTie("/autopilot/locks/altitude", getAPAltitudeLock, setAPAltitudeLock);
-    fgSetArchivable("/autopilot/locks/altitude");
-    fgTie("/autopilot/settings/altitude-ft", getAPAltitude, setAPAltitude);
-    fgSetArchivable("/autopilot/settings/altitude-ft");
-    fgTie("/autopilot/locks/glide-slope", getAPGSLock, setAPGSLock);
-    fgSetDouble("/autopilot/settings/altitude-ft", 3000.0f);
-    fgSetArchivable("/autopilot/locks/glide-slope");
-    fgTie("/autopilot/locks/terrain", getAPTerrainLock, setAPTerrainLock);
-    fgSetArchivable("/autopilot/locks/terrain");
-    fgTie("/autopilot/settings/climb-rate-fpm", getAPClimb, setAPClimb, false);
-    fgSetArchivable("/autopilot/settings/climb-rate-fpm");
-    fgTie("/autopilot/locks/heading", getAPHeadingLock, setAPHeadingLock);
-    fgSetArchivable("/autopilot/locks/heading");
-    fgTie("/autopilot/settings/heading-bug-deg",
-       getAPHeadingBug, setAPHeadingBug);
-    fgSetArchivable("/autopilot/settings/heading-bug-deg");
-    fgSetDouble("/autopilot/settings/heading-bug-deg", 0.0f);
-    fgTie("/autopilot/locks/wing-leveler", getAPWingLeveler, setAPWingLeveler);
-    fgSetArchivable("/autopilot/locks/wing-leveler");
-    fgTie("/autopilot/locks/nav[0]", getAPNAV1Lock, setAPNAV1Lock);
-    fgSetArchivable("/autopilot/locks/nav[0]");
-    fgTie("/autopilot/locks/auto-throttle",
-       getAPAutoThrottleLock, setAPAutoThrottleLock);
-    fgSetArchivable("/autopilot/locks/auto-throttle");
-    fgTie("/autopilot/control-overrides/rudder",
-       getAPRudderControl, setAPRudderControl);
-    fgSetArchivable("/autopilot/control-overrides/rudder");
-    fgTie("/autopilot/control-overrides/elevator",
-       getAPElevatorControl, setAPElevatorControl);
-    fgSetArchivable("/autopilot/control-overrides/elevator");
-    fgTie("/autopilot/control-overrides/throttle",
-       getAPThrottleControl, setAPThrottleControl);
-    fgSetArchivable("/autopilot/control-overrides/throttle");
 
+void FGAutopilot::init ()
+{
+    SG_LOG( SG_AUTOPILOT, SG_INFO, "Init AutoPilot Subsystem" );
 
     // bind data input property nodes...
     latitude_node = fgGetNode("/position/latitude-deg", true);
@@ -341,9 +298,63 @@ void FGAutopilot::init() {
 #endif  // !defined( USING_SLIDER_CLASS )
 
     update_old_control_values();
-       
 };
 
+void
+FGAutopilot::bind ()
+{
+    // Autopilot control property get/set bindings
+    fgTie("/autopilot/locks/altitude", this,
+         &FGAutopilot::getAPAltitudeLock, &FGAutopilot::setAPAltitudeLock);
+    fgSetArchivable("/autopilot/locks/altitude");
+    fgTie("/autopilot/settings/altitude-ft", this,
+         &FGAutopilot::getAPAltitude, &FGAutopilot::setAPAltitude);
+    fgSetArchivable("/autopilot/settings/altitude-ft");
+    fgTie("/autopilot/locks/glide-slope", this,
+         &FGAutopilot::getAPGSLock, &FGAutopilot::setAPGSLock);
+    fgSetArchivable("/autopilot/locks/glide-slope");
+    fgSetDouble("/autopilot/settings/altitude-ft", 3000.0f);
+    fgTie("/autopilot/locks/terrain", this,
+         &FGAutopilot::getAPTerrainLock, &FGAutopilot::setAPTerrainLock);
+    fgSetArchivable("/autopilot/locks/terrain");
+    fgTie("/autopilot/settings/climb-rate-fpm", this,
+         &FGAutopilot::getAPClimb, &FGAutopilot::setAPClimb, false);
+    fgSetArchivable("/autopilot/settings/climb-rate-fpm");
+    fgTie("/autopilot/locks/heading", this,
+         &FGAutopilot::getAPHeadingLock, &FGAutopilot::setAPHeadingLock);
+    fgSetArchivable("/autopilot/locks/heading");
+    fgTie("/autopilot/settings/heading-bug-deg", this,
+         &FGAutopilot::getAPHeadingBug, &FGAutopilot::setAPHeadingBug);
+    fgSetArchivable("/autopilot/settings/heading-bug-deg");
+    fgSetDouble("/autopilot/settings/heading-bug-deg", 0.0f);
+    fgTie("/autopilot/locks/wing-leveler", this,
+         &FGAutopilot::getAPWingLeveler, &FGAutopilot::setAPWingLeveler);
+    fgSetArchivable("/autopilot/locks/wing-leveler");
+    fgTie("/autopilot/locks/nav[0]", this,
+         &FGAutopilot::getAPNAV1Lock, &FGAutopilot::setAPNAV1Lock);
+    fgSetArchivable("/autopilot/locks/nav[0]");
+    fgTie("/autopilot/locks/auto-throttle", this,
+         &FGAutopilot::getAPAutoThrottleLock,
+         &FGAutopilot::setAPAutoThrottleLock);
+    fgSetArchivable("/autopilot/locks/auto-throttle");
+    fgTie("/autopilot/control-overrides/rudder", this,
+         &FGAutopilot::getAPRudderControl,
+         &FGAutopilot::setAPRudderControl);
+    fgSetArchivable("/autopilot/control-overrides/rudder");
+    fgTie("/autopilot/control-overrides/elevator", this,
+         &FGAutopilot::getAPElevatorControl,
+         &FGAutopilot::setAPElevatorControl);
+    fgSetArchivable("/autopilot/control-overrides/elevator");
+    fgTie("/autopilot/control-overrides/throttle", this,
+         &FGAutopilot::getAPThrottleControl,
+         &FGAutopilot::setAPThrottleControl);
+    fgSetArchivable("/autopilot/control-overrides/throttle");
+}
+
+void
+FGAutopilot::unbind ()
+{
+}
 
 // Reset the autopilot system
 void FGAutopilot::reset() {
@@ -406,7 +417,9 @@ static double LinearExtrapolate( double x, double x1, double y1, double x2, doub
 };
 
 
-int FGAutopilot::run() {
+void
+FGAutopilot::update (int dt)
+{
     // Remove the following lines when the calling funcitons start
     // passing in the data pointer
 
@@ -447,9 +460,6 @@ int FGAutopilot::run() {
     // heading hold
     if ( heading_hold == true ) {
        if ( heading_mode == FG_DG_HEADING_LOCK ) {
-           // cout << "DG heading = " << FGSteam::get_DG_deg()
-           //      << " DG error = " << FGSteam::get_DG_err() << endl;
-
            TargetHeading = DGTargetHeading + FGSteam::get_DG_err();
            while ( TargetHeading <   0.0 ) { TargetHeading += 360.0; }
            while ( TargetHeading > 360.0 ) { TargetHeading -= 360.0; }
@@ -503,7 +513,6 @@ int FGAutopilot::run() {
            while ( TargetHeading > 360.0 ) { TargetHeading -= 360.0; }
 
            MakeTargetHeadingStr( TargetHeading );
-           // cout << "target course (true) = " << TargetHeading << endl;
        } else if ( heading_mode == FG_HEADING_WAYPOINT ) {
            // update target heading to waypoint
 
@@ -542,9 +551,6 @@ int FGAutopilot::run() {
                // corrected_course = course - wp_course;
                TargetHeading = NormalizeDegrees(wp_course);
            } else {
-               cout << "Reached waypoint within " << wp_distance << "meters"
-                    << endl;
-
                // pop off this waypoint from the list
                if ( globals->get_route()->size() ) {
                    globals->get_route()->delete_first();
@@ -570,7 +576,6 @@ int FGAutopilot::run() {
        if ( heading_mode == FG_TC_HEADING_LOCK ) {
            // drive the turn coordinator to zero
            double turn = FGSteam::get_TC_std();
-           // cout << "turn rate = " << turn << endl;
            double AileronSet = -turn / 2.0;
             SG_CLAMP_RANGE( AileronSet, -1.0, 1.0 );
            globals->get_controls()->set_aileron( AileronSet );
@@ -660,25 +665,18 @@ int FGAutopilot::run() {
            double y = (altitude_node->getDoubleValue()
                        - current_radiostack->get_nav1_elev()) * SG_FEET_TO_METER;
            double current_angle = atan2( y, x ) * SGD_RADIANS_TO_DEGREES;
-           // cout << "current angle = " << current_angle << endl;
 
            double target_angle = current_radiostack->get_nav1_target_gs();
-           // cout << "target angle = " << target_angle << endl;
 
            double gs_diff = target_angle - current_angle;
-           // cout << "difference from desired = " << gs_diff << endl;
 
            // convert desired vertical path angle into a climb rate
            double des_angle = current_angle - 10 * gs_diff;
-           // cout << "desired angle = " << des_angle << endl;
 
            // convert to meter/min
-           // cout << "raw ground speed = " << cur_fdm_state->get_V_ground_speed() << endl;
            double horiz_vel = cur_fdm_state->get_V_ground_speed()
                * SG_FEET_TO_METER * 60.0;
-           // cout << "Horizontal vel = " << horiz_vel << endl;
            climb_rate = -sin( des_angle * SGD_DEGREES_TO_RADIANS ) * horiz_vel;
-           // cout << "climb_rate = " << climb_rate << endl;
            /* climb_error_accum += gs_diff * 2.0; */
            /* climb_rate = gs_diff * 200.0 + climb_error_accum; */
        } else if ( altitude_mode == FG_ALTITUDE_TERRAIN ) {
@@ -686,10 +684,6 @@ int FGAutopilot::run() {
            climb_rate =
                ( TargetAGL - altitude_agl_node->getDoubleValue()
                   * SG_FEET_TO_METER ) * 16.0;
-           // cout << "target agl = " << TargetAGL 
-           //      << "  current agl = " << fgAPget_agl() 
-           //      << "  target climb rate = " << climb_rate 
-           //      << endl;
        } else {
            // just try to zero out rate of climb ...
            climb_rate = 0.0;
@@ -729,13 +723,6 @@ int FGAutopilot::run() {
                 = -fabs(TargetDescentRate->getFloatValue() * SG_FEET_TO_METER);
        }
 
-       // cout << "Target climb rate = " << TargetClimbRate->getFloatValue() << endl;
-       // cout << "given our speed, modified desired climb rate = "
-       //      << climb_rate * SG_METER_TO_FEET 
-       //      << " fpm" << endl;
-        // cout << "Current climb rate = "
-        //      << vertical_speed_node->getDoubleValue() * 60 << " fpm" << endl;
-
        error = vertical_speed_node->getDoubleValue() * 60
             - climb_rate * SG_METER_TO_FEET;
 
@@ -752,11 +739,6 @@ int FGAutopilot::run() {
        prop_error = error;
        prop_adj = prop_error / elevator_adj_factor->getDoubleValue();
 
-        // cout << "Error=" << error << endl;
-        // cout << "integral_error=" << int_error << endl;
-        // cout << "integral_contrib=" << integral_contrib->getFloatValue() << endl;
-        // cout << "Proportional Adj=" << prop_adj << endl;
-        // cout << "Integral Adj" << int_adj << endl;
        total_adj = ((double) 1.0 - (double) integral_contrib->getFloatValue()) * prop_adj
             + (double) integral_contrib->getFloatValue() * int_adj;
 
@@ -772,8 +754,6 @@ int FGAutopilot::run() {
                      / (1 - zero_pitch_throttle->getFloatValue()))
                      * zero_pitch_trim_full_throttle->getFloatValue();
 
-        // cout << "Total Adj" << total_adj << endl;
-
        globals->get_controls()->set_elevator_trim( total_adj );
     }
 
@@ -857,8 +837,6 @@ int FGAutopilot::run() {
        
     // Ok, we are done
     SG_LOG( SG_ALL, SG_DEBUG, "FGAutopilot::run( returns )" );
-
-    return 0;
 }
 
 
@@ -950,60 +928,9 @@ void FGAutopilot::set_AltitudeMode( fgAutoAltitudeMode mode ) {
 }
 
 
-#if 0
-static inline double get_aoa( void ) {
-    return( cur_fdm_state->get_Gamma_vert_rad() * SGD_RADIANS_TO_DEGREES );
-}
-
-static inline double fgAPget_latitude( void ) {
-    return( cur_fdm_state->get_Latitude() * SGD_RADIANS_TO_DEGREES );
-}
-
-static inline double fgAPget_longitude( void ) {
-    return( cur_fdm_state->get_Longitude() * SGD_RADIANS_TO_DEGREES );
-}
-
-static inline double fgAPget_roll( void ) {
-    return( cur_fdm_state->get_Phi() * SGD_RADIANS_TO_DEGREES );
-}
-
-static inline double get_pitch( void ) {
-    return( cur_fdm_state->get_Theta() );
-}
-
-double fgAPget_heading( void ) {
-    return( cur_fdm_state->get_Psi() * SGD_RADIANS_TO_DEGREES );
-}
-
-static inline double fgAPget_altitude( void ) {
-    return( cur_fdm_state->get_Altitude() * SG_FEET_TO_METER );
-}
-
-static inline double fgAPget_climb( void ) {
-    // return in meters per minute
-    return( cur_fdm_state->get_Climb_Rate() * SG_FEET_TO_METER * 60 );
-}
-
-static inline double get_sideslip( void ) {
-    return( cur_fdm_state->get_Beta() );
-}
-
-static inline double fgAPget_agl( void ) {
-    double agl;
-
-    agl = cur_fdm_state->get_Altitude() * SG_FEET_TO_METER
-       - scenery.get_cur_elev();
-
-    return( agl );
-}
-#endif
-
-
 void FGAutopilot::AltitudeSet( double new_altitude ) {
     double target_alt = new_altitude;
 
-    // cout << "new altitude = " << new_altitude << endl;
-
     if ( fgGetString("/sim/startup/units") == "feet" ) {
        target_alt = new_altitude * SG_FEET_TO_METER;
     }
@@ -1015,8 +942,6 @@ void FGAutopilot::AltitudeSet( double new_altitude ) {
     TargetAltitude = target_alt;
     altitude_mode = FG_ALTITUDE_LOCK;
 
-    // cout << "TargetAltitude = " << TargetAltitude << endl;
-
     if ( fgGetString("/sim/startup/units") == "feet" ) {
        target_alt *= SG_METER_TO_FEET;
     }
@@ -1039,10 +964,6 @@ void FGAutopilot::AltitudeAdjust( double inc )
        target_agl = TargetAGL;
     }
 
-    // cout << "target_agl = " << target_agl << endl;
-    // cout << "target_agl / inc = " << target_agl / inc << endl;
-    // cout << "(int)(target_agl / inc) = " << (int)(target_agl / inc) << endl;
-
     if ( fabs((int)(target_alt / inc) * inc - target_alt) < SG_EPSILON ) {
        target_alt += inc;
     } else {
@@ -1133,3 +1054,311 @@ void FGAutopilot::set_AutoThrottleEnabled( bool value ) {
     SG_LOG( SG_COCKPIT, SG_INFO, " fgAPSetAutoThrottle: ("
            << auto_throttle << ") " << TargetSpeed );
 }
+
+
+
+\f
+////////////////////////////////////////////////////////////////////////
+// Kludged methods for tying to properties.
+//
+// These should change eventually; they all used to be static
+// functions.
+////////////////////////////////////////////////////////////////////////
+
+/**
+ * Get the autopilot altitude lock (true=on).
+ */
+bool
+FGAutopilot::getAPAltitudeLock () const
+{
+    return (get_AltitudeEnabled() &&
+           get_AltitudeMode()
+           == FGAutopilot::FG_ALTITUDE_LOCK);
+}
+
+
+/**
+ * Set the autopilot altitude lock (true=on).
+ */
+void
+FGAutopilot::setAPAltitudeLock (bool lock)
+{
+  if (lock)
+    set_AltitudeMode(FGAutopilot::FG_ALTITUDE_LOCK);
+  if (get_AltitudeMode() == FGAutopilot::FG_ALTITUDE_LOCK)
+    set_AltitudeEnabled(lock);
+}
+
+
+/**
+ * Get the autopilot target altitude in feet.
+ */
+double
+FGAutopilot::getAPAltitude () const
+{
+  return get_TargetAltitude() * SG_METER_TO_FEET;
+}
+
+
+/**
+ * Set the autopilot target altitude in feet.
+ */
+void
+FGAutopilot::setAPAltitude (double altitude)
+{
+  set_TargetAltitude( altitude * SG_FEET_TO_METER );
+}
+
+/**
+ * Get the autopilot altitude lock (true=on).
+ */
+bool
+FGAutopilot::getAPGSLock () const
+{
+    return (get_AltitudeEnabled() &&
+           (get_AltitudeMode()
+            == FGAutopilot::FG_ALTITUDE_GS1));
+}
+
+
+/**
+ * Set the autopilot altitude lock (true=on).
+ */
+void
+FGAutopilot::setAPGSLock (bool lock)
+{
+  if (lock)
+    set_AltitudeMode(FGAutopilot::FG_ALTITUDE_GS1);
+  if (get_AltitudeMode() == FGAutopilot::FG_ALTITUDE_GS1)
+    set_AltitudeEnabled(lock);
+}
+
+
+/**
+ * Get the autopilot terrain lock (true=on).
+ */
+bool
+FGAutopilot::getAPTerrainLock () const
+{
+    return (get_AltitudeEnabled() &&
+           (get_AltitudeMode()
+            == FGAutopilot::FG_ALTITUDE_TERRAIN));
+}
+
+
+/**
+ * Set the autopilot terrain lock (true=on).
+ */
+void
+FGAutopilot::setAPTerrainLock (bool lock)
+{
+  if (lock) {
+    set_AltitudeMode(FGAutopilot::FG_ALTITUDE_TERRAIN);
+    set_TargetAGL(fgGetFloat("/position/altitude-agl-ft") *
+                 SG_FEET_TO_METER);
+  }
+  if (get_AltitudeMode() == FGAutopilot::FG_ALTITUDE_TERRAIN)
+    set_AltitudeEnabled(lock);
+}
+
+
+/**
+ * Get the autopilot target altitude in feet.
+ */
+double
+FGAutopilot::getAPClimb () const
+{
+  return get_TargetClimbRate() * SG_METER_TO_FEET;
+}
+
+
+/**
+ * Set the autopilot target altitude in feet.
+ */
+void
+FGAutopilot::setAPClimb (double rate)
+{
+    set_TargetClimbRate( rate * SG_FEET_TO_METER );
+}
+
+
+/**
+ * Get the autopilot heading lock (true=on).
+ */
+bool
+FGAutopilot::getAPHeadingLock () const
+{
+    return
+      (get_HeadingEnabled() &&
+       get_HeadingMode() == DEFAULT_AP_HEADING_LOCK);
+}
+
+
+/**
+ * Set the autopilot heading lock (true=on).
+ */
+void
+FGAutopilot::setAPHeadingLock (bool lock)
+{
+  if (lock)
+    set_HeadingMode(DEFAULT_AP_HEADING_LOCK);
+  if (get_HeadingMode() == DEFAULT_AP_HEADING_LOCK)
+    set_HeadingEnabled(lock);
+}
+
+
+/**
+ * Get the autopilot heading bug in degrees.
+ */
+double
+FGAutopilot::getAPHeadingBug () const
+{
+  return get_DGTargetHeading();
+}
+
+
+/**
+ * Set the autopilot heading bug in degrees.
+ */
+void
+FGAutopilot::setAPHeadingBug (double heading)
+{
+  set_DGTargetHeading( heading );
+}
+
+
+/**
+ * Get the autopilot wing leveler lock (true=on).
+ */
+bool
+FGAutopilot::getAPWingLeveler () const
+{
+    return
+      (get_HeadingEnabled() &&
+       get_HeadingMode() == FGAutopilot::FG_TC_HEADING_LOCK);
+}
+
+
+/**
+ * Set the autopilot wing leveler lock (true=on).
+ */
+void
+FGAutopilot::setAPWingLeveler (bool lock)
+{
+    if (lock)
+       set_HeadingMode(FGAutopilot::FG_TC_HEADING_LOCK);
+    if (get_HeadingMode() == FGAutopilot::FG_TC_HEADING_LOCK)
+      set_HeadingEnabled(lock);
+}
+
+/**
+ * Return true if the autopilot is locked to NAV1.
+ */
+bool
+FGAutopilot::getAPNAV1Lock () const
+{
+  return
+    (get_HeadingEnabled() &&
+     get_HeadingMode() == FGAutopilot::FG_HEADING_NAV1);
+}
+
+
+/**
+ * Set the autopilot NAV1 lock.
+ */
+void
+FGAutopilot::setAPNAV1Lock (bool lock)
+{
+  if (lock)
+    set_HeadingMode(FGAutopilot::FG_HEADING_NAV1);
+  if (get_HeadingMode() == FGAutopilot::FG_HEADING_NAV1)
+    set_HeadingEnabled(lock);
+}
+
+/**
+ * Get the autopilot autothrottle lock.
+ */
+bool
+FGAutopilot::getAPAutoThrottleLock () const
+{
+  return get_AutoThrottleEnabled();
+}
+
+
+/**
+ * Set the autothrottle lock.
+ */
+void
+FGAutopilot::setAPAutoThrottleLock (bool lock)
+{
+  set_AutoThrottleEnabled(lock);
+}
+
+
+// kludge
+double
+FGAutopilot::getAPRudderControl () const
+{
+    if (getAPHeadingLock())
+        return get_TargetHeading();
+    else
+        return globals->get_controls()->get_rudder();
+}
+
+// kludge
+void
+FGAutopilot::setAPRudderControl (double value)
+{
+    if (getAPHeadingLock()) {
+        SG_LOG(SG_GENERAL, SG_DEBUG, "setAPRudderControl " << value );
+        value -= get_TargetHeading();
+        HeadingAdjust(value < 0.0 ? -1.0 : 1.0);
+    } else {
+        globals->get_controls()->set_rudder(value);
+    }
+}
+
+// kludge
+double
+FGAutopilot::getAPElevatorControl () const
+{
+  if (getAPAltitudeLock())
+      return get_TargetAltitude();
+  else
+    return globals->get_controls()->get_elevator();
+}
+
+// kludge
+void
+FGAutopilot::setAPElevatorControl (double value)
+{
+    if (value != 0 && getAPAltitudeLock()) {
+        SG_LOG(SG_GENERAL, SG_DEBUG, "setAPElevatorControl " << value );
+        value -= get_TargetAltitude();
+        AltitudeAdjust(value < 0.0 ? 100.0 : -100.0);
+    } else {
+        globals->get_controls()->set_elevator(value);
+    }
+}
+
+// kludge
+double
+FGAutopilot::getAPThrottleControl () const
+{
+  if (getAPAutoThrottleLock())
+    return 0.0;                        // always resets
+  else
+    return globals->get_controls()->get_throttle(0);
+}
+
+// kludge
+void
+FGAutopilot::setAPThrottleControl (double value)
+{
+  if (getAPAutoThrottleLock())
+    AutoThrottleAdjust(value < 0.0 ? -0.01 : 0.01);
+  else
+    globals->get_controls()->set_throttle(FGControls::ALL_ENGINES, value);
+}
+
+// end of newauto.cxx
index 08fa318c22b055e101202bc0320ac42866f09cfc..6097303c1b727ae05f7f4afe116f4d31331dbd0e 100644 (file)
 #include <simgear/misc/props.hxx>
 #include <simgear/route/waypoint.hxx>
 
+#include <Main/fgfs.hxx>
 #include <Main/fg_props.hxx>
 
 // Structures
-class FGAutopilot {
+class FGAutopilot : public FGSubsystem
+{
 
 public:
 
@@ -142,15 +144,19 @@ public:
     // destructor
     ~FGAutopilot();
 
-    // Initialize autopilot system
-    void init();
+\f
+    ////////////////////////////////////////////////////////////////////
+    // Implementation of FGSubsystem.
+    ////////////////////////////////////////////////////////////////////
+
+    void init ();
+    void bind ();
+    void unbind ();
+    void update (int dt);
 
     // Reset the autopilot system
     void reset(void);
 
-    // run an interation of the autopilot (updates control positions)
-    int run();
-
     void AltitudeSet( double new_altitude );
     void AltitudeAdjust( double inc );
     void HeadingAdjust( double inc );
@@ -227,10 +233,37 @@ public:
     inline double get_RollOutSmooth() const { return RollOutSmooth; }
     inline void set_RollOutSmooth( double val ) { RollOutSmooth = val; }
 
-};
+private:
+
+    bool getAPAltitudeLock () const;
+    void setAPAltitudeLock (bool lock);
+    double getAPAltitude () const;
+    void setAPAltitude (double altitude);
+    bool getAPGSLock () const;
+    void setAPGSLock (bool lock);
+    bool getAPTerrainLock () const;
+    void setAPTerrainLock (bool lock);
+    double getAPClimb () const;
+    void setAPClimb (double rate);
+    bool getAPHeadingLock () const;
+    void setAPHeadingLock (bool lock);
+    double getAPHeadingBug () const;
+    void setAPHeadingBug (double heading);
+    bool getAPWingLeveler () const;
+    void setAPWingLeveler (bool lock);
+    bool getAPNAV1Lock () const;
+    void setAPNAV1Lock (bool lock);
+    bool getAPAutoThrottleLock () const;
+    void setAPAutoThrottleLock (bool lock);
+    double getAPRudderControl () const;
+    void setAPRudderControl (double value);
+    double getAPElevatorControl () const;
+    void setAPElevatorControl (double value);
+    double getAPThrottleControl () const;
+    void setAPThrottleControl (double value);
 
+};
 
-extern FGAutopilot *current_autopilot;
 
 #define DEFAULT_AP_HEADING_LOCK FGAutopilot::FG_DG_HEADING_LOCK
 // #define DEFAULT_AP_HEADING_LOCK FGAutopilot::FG_TRUE_HEADING_LOCK
@@ -240,304 +273,4 @@ extern FGAutopilot *current_autopilot;
  * static functions for autopilot properties
  */
 
-/**
- * Get the autopilot altitude lock (true=on).
- */
-static bool
-getAPAltitudeLock ()
-{
-    return (current_autopilot->get_AltitudeEnabled() &&
-           current_autopilot->get_AltitudeMode()
-           == FGAutopilot::FG_ALTITUDE_LOCK);
-}
-
-
-/**
- * Set the autopilot altitude lock (true=on).
- */
-static void
-setAPAltitudeLock (bool lock)
-{
-  if (lock)
-    current_autopilot->set_AltitudeMode(FGAutopilot::FG_ALTITUDE_LOCK);
-  if (current_autopilot->get_AltitudeMode() == FGAutopilot::FG_ALTITUDE_LOCK)
-    current_autopilot->set_AltitudeEnabled(lock);
-}
-
-
-/**
- * Get the autopilot target altitude in feet.
- */
-static double
-getAPAltitude ()
-{
-  return current_autopilot->get_TargetAltitude() * SG_METER_TO_FEET;
-}
-
-
-/**
- * Set the autopilot target altitude in feet.
- */
-static void
-setAPAltitude (double altitude)
-{
-  current_autopilot->set_TargetAltitude( altitude * SG_FEET_TO_METER );
-}
-
-/**
- * Get the autopilot altitude lock (true=on).
- */
-static bool
-getAPGSLock ()
-{
-    return (current_autopilot->get_AltitudeEnabled() &&
-           (current_autopilot->get_AltitudeMode()
-            == FGAutopilot::FG_ALTITUDE_GS1));
-}
-
-
-/**
- * Set the autopilot altitude lock (true=on).
- */
-static void
-setAPGSLock (bool lock)
-{
-  if (lock)
-    current_autopilot->set_AltitudeMode(FGAutopilot::FG_ALTITUDE_GS1);
-  if (current_autopilot->get_AltitudeMode() == FGAutopilot::FG_ALTITUDE_GS1)
-    current_autopilot->set_AltitudeEnabled(lock);
-}
-
-
-/**
- * Get the autopilot terrain lock (true=on).
- */
-static bool
-getAPTerrainLock ()
-{
-    return (current_autopilot->get_AltitudeEnabled() &&
-           (current_autopilot->get_AltitudeMode()
-            == FGAutopilot::FG_ALTITUDE_TERRAIN));
-}
-
-
-/**
- * Set the autopilot terrain lock (true=on).
- */
-static void
-setAPTerrainLock (bool lock)
-{
-  if (lock) {
-    current_autopilot->set_AltitudeMode(FGAutopilot::FG_ALTITUDE_TERRAIN);
-    current_autopilot
-      ->set_TargetAGL(fgGetFloat("/position/altitude-agl-ft") *
-                     SG_FEET_TO_METER);
-    cout << "Target AGL = "
-        << fgGetFloat("/position/altitude-agl-ft") * SG_FEET_TO_METER
-        << endl;
-  }
-  if (current_autopilot->get_AltitudeMode() == FGAutopilot::FG_ALTITUDE_TERRAIN)
-    current_autopilot->set_AltitudeEnabled(lock);
-}
-
-
-/**
- * Get the autopilot target altitude in feet.
- */
-static double
-getAPClimb ()
-{
-  return current_autopilot->get_TargetClimbRate() * SG_METER_TO_FEET;
-}
-
-
-/**
- * Set the autopilot target altitude in feet.
- */
-static void
-setAPClimb (double rate)
-{
-    current_autopilot->set_TargetClimbRate( rate * SG_FEET_TO_METER );
-}
-
-
-/**
- * Get the autopilot heading lock (true=on).
- */
-static bool
-getAPHeadingLock ()
-{
-    return
-      (current_autopilot->get_HeadingEnabled() &&
-       current_autopilot->get_HeadingMode() == DEFAULT_AP_HEADING_LOCK);
-}
-
-
-/**
- * Set the autopilot heading lock (true=on).
- */
-static void
-setAPHeadingLock (bool lock)
-{
-  if (lock)
-    current_autopilot->set_HeadingMode(DEFAULT_AP_HEADING_LOCK);
-  if (current_autopilot->get_HeadingMode() == DEFAULT_AP_HEADING_LOCK)
-    current_autopilot->set_HeadingEnabled(lock);
-}
-
-
-/**
- * Get the autopilot heading bug in degrees.
- */
-static double
-getAPHeadingBug ()
-{
-  return current_autopilot->get_DGTargetHeading();
-}
-
-
-/**
- * Set the autopilot heading bug in degrees.
- */
-static void
-setAPHeadingBug (double heading)
-{
-  current_autopilot->set_DGTargetHeading( heading );
-}
-
-
-/**
- * Get the autopilot wing leveler lock (true=on).
- */
-static bool
-getAPWingLeveler ()
-{
-    return
-      (current_autopilot->get_HeadingEnabled() &&
-       current_autopilot->get_HeadingMode() == FGAutopilot::FG_TC_HEADING_LOCK);
-}
-
-
-/**
- * Set the autopilot wing leveler lock (true=on).
- */
-static void
-setAPWingLeveler (bool lock)
-{
-    if (lock)
-       current_autopilot->set_HeadingMode(FGAutopilot::FG_TC_HEADING_LOCK);
-    if (current_autopilot->get_HeadingMode() == FGAutopilot::FG_TC_HEADING_LOCK)
-      current_autopilot->set_HeadingEnabled(lock);
-}
-
-/**
- * Return true if the autopilot is locked to NAV1.
- */
-static bool
-getAPNAV1Lock ()
-{
-  return
-    (current_autopilot->get_HeadingEnabled() &&
-     current_autopilot->get_HeadingMode() == FGAutopilot::FG_HEADING_NAV1);
-}
-
-
-/**
- * Set the autopilot NAV1 lock.
- */
-static void
-setAPNAV1Lock (bool lock)
-{
-  if (lock)
-    current_autopilot->set_HeadingMode(FGAutopilot::FG_HEADING_NAV1);
-  if (current_autopilot->get_HeadingMode() == FGAutopilot::FG_HEADING_NAV1)
-    current_autopilot->set_HeadingEnabled(lock);
-}
-
-/**
- * Get the autopilot autothrottle lock.
- */
-static bool
-getAPAutoThrottleLock ()
-{
-  return current_autopilot->get_AutoThrottleEnabled();
-}
-
-
-/**
- * Set the autothrottle lock.
- */
-static void
-setAPAutoThrottleLock (bool lock)
-{
-  current_autopilot->set_AutoThrottleEnabled(lock);
-}
-
-
-// kludge
-static double
-getAPRudderControl ()
-{
-    if (getAPHeadingLock())
-        return current_autopilot->get_TargetHeading();
-    else
-        return globals->get_controls()->get_rudder();
-}
-
-// kludge
-static void
-setAPRudderControl (double value)
-{
-    if (getAPHeadingLock()) {
-        SG_LOG(SG_GENERAL, SG_DEBUG, "setAPRudderControl " << value );
-        value -= current_autopilot->get_TargetHeading();
-        current_autopilot->HeadingAdjust(value < 0.0 ? -1.0 : 1.0);
-    } else {
-        globals->get_controls()->set_rudder(value);
-    }
-}
-
-// kludge
-static double
-getAPElevatorControl ()
-{
-  if (getAPAltitudeLock())
-      return current_autopilot->get_TargetAltitude();
-  else
-    return globals->get_controls()->get_elevator();
-}
-
-// kludge
-static void
-setAPElevatorControl (double value)
-{
-    if (value != 0 && getAPAltitudeLock()) {
-        SG_LOG(SG_GENERAL, SG_DEBUG, "setAPElevatorControl " << value );
-        value -= current_autopilot->get_TargetAltitude();
-        current_autopilot->AltitudeAdjust(value < 0.0 ? 100.0 : -100.0);
-    } else {
-        globals->get_controls()->set_elevator(value);
-    }
-}
-
-// kludge
-static double
-getAPThrottleControl ()
-{
-  if (getAPAutoThrottleLock())
-    return 0.0;                        // always resets
-  else
-    return globals->get_controls()->get_throttle(0);
-}
-
-// kludge
-static void
-setAPThrottleControl (double value)
-{
-  if (getAPAutoThrottleLock())
-    current_autopilot->AutoThrottleAdjust(value < 0.0 ? -0.01 : 0.01);
-  else
-    globals->get_controls()->set_throttle(FGControls::ALL_ENGINES, value);
-}
-
 #endif // _NEWAUTO_HXX
index 88608312ca46d45ad0ea931c4496f667de9db13f..fb7c29d1c0883dac6ef3a0aac7487488af21c2e8 100644 (file)
@@ -1181,31 +1181,31 @@ void fgUpdateHUD( GLfloat x_start, GLfloat y_start,
     // char scratch[128];
     // HUD_TextList.add( fgText( "AUTOPILOT", 20, apY) );
     // apY -= 15;
-    if( current_autopilot->get_HeadingEnabled() ) {
+    if( globals->get_autopilot()->get_HeadingEnabled() ) {
         HUD_TextList.add( fgText( 40, apY, 
-                                  current_autopilot->get_TargetHeadingStr()) );
+                                  globals->get_autopilot()->get_TargetHeadingStr()) );
         apY -= 15;
     }
-    if( current_autopilot->get_AltitudeEnabled() ) {
+    if( globals->get_autopilot()->get_AltitudeEnabled() ) {
         HUD_TextList.add( fgText( 40, apY, 
-                                  current_autopilot->get_TargetAltitudeStr()) );
+                                  globals->get_autopilot()->get_TargetAltitudeStr()) );
         apY -= 15;
     }
-    if( current_autopilot->get_HeadingMode() == 
+    if( globals->get_autopilot()->get_HeadingMode() == 
         FGAutopilot::FG_HEADING_WAYPOINT )
     {
         char *wpstr;
-        wpstr = current_autopilot->get_TargetWP1Str();
+        wpstr = globals->get_autopilot()->get_TargetWP1Str();
         if ( strlen( wpstr ) ) {
             HUD_TextList.add( fgText( 40, apY, wpstr ) );
             apY -= 15;
         }
-        wpstr = current_autopilot->get_TargetWP2Str();
+        wpstr = globals->get_autopilot()->get_TargetWP2Str();
         if ( strlen( wpstr ) ) {
             HUD_TextList.add( fgText( 40, apY, wpstr ) );
             apY -= 15;
         }
-        wpstr = current_autopilot->get_TargetWP3Str();
+        wpstr = globals->get_autopilot()->get_TargetWP3Str();
         if ( strlen( wpstr ) ) {
             HUD_TextList.add( fgText( 40, apY, wpstr ) );
                 apY -= 15;
index 9a08c457b8bbdf17018ee562b1e3d015b90cf17d..fa6609c1e903d27db02e57386eaf89e89c5b730f 100644 (file)
@@ -224,11 +224,11 @@ static inline float get_elevator() {
 }
 
 static inline bool AP_HeadingEnabled() {
-       return current_autopilot->get_HeadingEnabled();
+       return globals->get_autopilot()->get_HeadingEnabled();
 }
 
 static inline bool AP_AltitudeEnabled() {
-       return current_autopilot->get_AltitudeEnabled();
+       return globals->get_autopilot()->get_AltitudeEnabled();
 }
 
 void TurnCursorOn( void )
index 06122defdc0dd2380a1306ddd1e379d2740c3bca..7dfbc57b49902779a4920e35ef0784bd404424f1 100644 (file)
@@ -283,13 +283,13 @@ FGInput::doKey (int k, int modifiers, int x, int y)
 // START SPECIALS
 
         case 256+GLUT_KEY_F6: // F6 toggles Autopilot target location
-           if ( current_autopilot->get_HeadingMode() !=
+           if ( globals->get_autopilot()->get_HeadingMode() !=
                 FGAutopilot::FG_HEADING_WAYPOINT ) {
-               current_autopilot->set_HeadingMode(
+               globals->get_autopilot()->set_HeadingMode(
                    FGAutopilot::FG_HEADING_WAYPOINT );
-               current_autopilot->set_HeadingEnabled( true );
+               globals->get_autopilot()->set_HeadingEnabled( true );
            } else {
-               current_autopilot->set_HeadingMode(
+               globals->get_autopilot()->set_HeadingMode(
                    FGAutopilot::FG_TC_HEADING_LOCK );
            }
            return;
index f3ec090787f621adf0d002b1052ff0bb55e91023..9b4bd9233ba0aecee77f752965373b7cf9bbe340 100644 (file)
@@ -964,10 +964,12 @@ bool fgInitSubsystems( void ) {
     // Initialize the autopilot subsystem.
     ////////////////////////////////////////////////////////////////////
 
-    current_autopilot = new FGAutopilot;
-    current_autopilot->init();
+    globals->set_autopilot(new FGAutopilot);
+    globals->get_autopilot()->init();
+    globals->get_autopilot()->bind();
 
-    // initialize the gui parts of the autopilot
+                               // FIXME: these should go in the
+                               // GUI initialization code, not here.
     fgAPAdjustInit();
     NewTgtAirportInit();
     NewHeadingInit();
@@ -1074,7 +1076,7 @@ void fgReInitSubsystems( void )
     fgInitView();
 
     globals->get_controls()->reset_all();
-    current_autopilot->reset();
+    globals->get_autopilot()->reset();
 
     fgUpdateSunPos();
     fgUpdateMoonPos();
index bbfe639399b004cbb8d3a62c071902ab13987444..46daa721f9591434b250408db5538595511eb72b 100644 (file)
@@ -49,6 +49,7 @@ class FGEnvironmentMgr;
 class FGEnvironment;
 class FGControls;
 class FGSoundMgr;
+class FGAutopilot;
 class FGFX;
 class FGViewMgr;
 class FGViewer;
@@ -98,6 +99,9 @@ private:
     // Magnetic Variation
     SGMagVar *mag;
 
+    // Current autopilot
+    FGAutopilot *autopilot;
+
     // Global autopilot "route"
     SGRoute *route;
 
@@ -178,6 +182,9 @@ public:
     inline SGMagVar *get_mag() const { return mag; }
     inline void set_mag( SGMagVar *m ) { mag = m; }
 
+    inline FGAutopilot *get_autopilot() const { return autopilot; }
+    inline void set_autopilot( FGAutopilot *ap) { autopilot = ap; }
+
     inline SGRoute *get_route() const { return route; }
     inline void set_route( SGRoute *r ) { route = r; }
 
index 21c2c5ed9124dd09ff25e041fb819f09dabac402..86d72daac6de165a8f47bcd86f72f5e254f8a647 100644 (file)
@@ -868,7 +868,7 @@ void fgUpdateTimeDepCalcs() {
        // cout << "multi_loop = " << multi_loop << endl;
        for ( i = 0; i < multi_loop * fgGetInt("/sim/speed-up"); ++i ) {
            // run Autopilot system
-           current_autopilot->run();
+           globals->get_autopilot()->update(0); // FIXME: use real dt
 
            // update FDM
            cur_fdm_state->update( 1 );