]> git.mxchange.org Git - flightgear.git/blobdiff - src/FDM/YASim/Rotor.cpp
latest updates from JSBSim
[flightgear.git] / src / FDM / YASim / Rotor.cpp
index 0e59f66104da75308a76985d6985cb06da122fd3..2a93a4457f4be5e9468ddad21d4784c31f455a4d 100644 (file)
@@ -8,10 +8,10 @@
 #include "Ground.hpp"
 #include "Rotor.hpp"
 
-#include STL_IOSTREAM
-#include STL_IOMANIP
+#include <iostream>
+#include <iomanip>
 
-SG_USING_STD(setprecision);
+using std::setprecision;
 
 #ifdef TEST_DEBUG
 #include <stdio.h>
@@ -114,7 +114,7 @@ Rotor::Rotor()
     _airfoil_drag_coefficient0=0;
     _airfoil_drag_coefficient1=0;
     for(i=0; i<2; i++)
-        _global_ground[i] =  0;
+        _global_ground[i] = _tilt_center[i] = 0;
     _global_ground[2] = 1;
     _global_ground[3] = -1e3;
     _incidence_stall_zero_speed=18*pi/180.;
@@ -137,6 +137,20 @@ Rotor::Rotor()
     _balance2=1;
     _properties_tied=0;
     _num_ground_contact_pos=0;
+    _directions_and_postions_dirty=true;
+    _tilt_yaw=0;
+    _tilt_roll=0;
+    _tilt_pitch=0;
+    _old_tilt_roll=0;
+    _old_tilt_pitch=0;
+    _old_tilt_yaw=0;
+    _min_tilt_yaw=0;
+    _min_tilt_pitch=0;
+    _min_tilt_roll=0;
+    _max_tilt_yaw=0;
+    _max_tilt_pitch=0;
+    _max_tilt_roll=0;
+    _downwash_factor=1;
 }
 
 Rotor::~Rotor()
@@ -164,13 +178,16 @@ void Rotor::inititeration(float dt,float omegarel,float ddt_omegarel,float *rot)
     _omega=_omegan*_omegarel; 
     _ddt_omega=_omegan*ddt_omegarel;
     int i;
+    float drot[3];
+    updateDirectionsAndPositions(drot);
+    Math::add3(rot,drot,drot);
     for(i=0; i<_rotorparts.size(); i++) {
         float s = Math::sin(float(2*pi*i/_number_of_parts+(_phi-pi/2.)*(_ccw?1:-1)));
         float c = Math::cos(float(2*pi*i/_number_of_parts+(_phi-pi/2.)*(_ccw?1:-1)));
         Rotorpart* r = (Rotorpart*)_rotorparts.get(i);
         r->setOmega(_omega);
         r->setDdtOmega(_ddt_omega);
-        r->inititeration(dt,rot);
+        r->inititeration(dt,drot);
         r->setCyclic(_cyclicail*c+_cyclicele*s);
     }
 
@@ -188,7 +205,7 @@ void Rotor::inititeration(float dt,float omegarel,float ddt_omegarel,float *rot)
     //update balance
     if ((_balance1*_balance2 < 0.97) && (_balance1>-1))
     {
-        _balance1-=(0.97-_balance1*_balance2)*(0.97-_balance1*_balance2)*0.00001;
+        _balance1-=(0.97-_balance1*_balance2)*(0.97-_balance1*_balance2)*0.005;
         if (_balance1<-1) _balance1=-1;
     }
 }
@@ -287,18 +304,18 @@ int Rotor::getValueforFGSet(int j,char *text,float *f)
                 else
                     if (j==4)
                     {
-                        sprintf(text,"/rotors/%s/debug/debugfge",_name);
-                        *f=_f_ge;
+                        sprintf(text,"/rotors/%s/tilt/pitch-deg",_name);
+                        *f=_tilt_pitch*180/pi;
                     }
                     else if (j==5)
                     {
-                        sprintf(text,"/rotors/%s/debug/debugfvs",_name);
-                        *f=_f_vs;
+                        sprintf(text,"/rotors/%s/tilt/roll-deg",_name);
+                        *f=_tilt_roll*180/pi;
                     }
                     else if (j==6)
                     {
-                        sprintf(text,"/rotors/%s/debug/debugftl",_name);
-                        *f=_f_tl;
+                        sprintf(text,"/rotors/%s/tilt/yaw-deg",_name);
+                        *f=_tilt_yaw*180/pi;
                     }
                     else if (j==7)
                     {
@@ -359,12 +376,12 @@ void Rotorgear::setEngineOn(int value)
 
 void Rotorgear::setRotorEngineMaxRelTorque(float lval)
 {
-    fgGetNode("/rotors/gear/max-rel-torque", true)->setDoubleValue(lval);
+    _max_rel_torque=lval;
 }
 
 void Rotorgear::setRotorRelTarget(float lval)
 {
-    fgGetNode("/rotors/gear/target-rel-rpm", true)->setDoubleValue(lval);
+    _target_rel_rpm=lval;
 }
 
 void Rotor::setAlpha0(float f)
@@ -511,6 +528,51 @@ void Rotor::setMinCollective(float value)
     _min_pitch=value/180*pi;
 }
 
+void Rotor::setMinTiltYaw(float value)
+{
+    _min_tilt_yaw=value/180*pi;
+}
+
+void Rotor::setMinTiltPitch(float value)
+{
+    _min_tilt_pitch=value/180*pi;
+}
+
+void Rotor::setMinTiltRoll(float value)
+{
+    _min_tilt_roll=value/180*pi;
+}
+
+void Rotor::setMaxTiltYaw(float value)
+{
+    _max_tilt_yaw=value/180*pi;
+}
+
+void Rotor::setMaxTiltPitch(float value)
+{
+    _max_tilt_pitch=value/180*pi;
+}
+
+void Rotor::setMaxTiltRoll(float value)
+{
+    _max_tilt_roll=value/180*pi;
+}
+
+void Rotor::setTiltCenterX(float value)
+{
+    _tilt_center[0] = value;
+}
+
+void Rotor::setTiltCenterY(float value)
+{
+    _tilt_center[1] = value;
+}
+
+void Rotor::setTiltCenterZ(float value)
+{
+    _tilt_center[2] = value;
+}
+
 void Rotor::setMaxCollective(float value)
 {
     _max_pitch=value/180*pi;
@@ -591,6 +653,11 @@ void Rotor::setRelLenHinge(float value)
     _rel_len_hinge=value;
 }
 
+void Rotor::setDownwashFactor(float value)
+{
+    _downwash_factor=value;
+}
+
 void Rotor::setAlphaoutput(int i, const char *text)
 {
     strncpy(_alphaoutput[i],text,255);
@@ -632,7 +699,7 @@ void Rotor::setGlobalGround(double *global_ground, float* global_vel)
     for(i=0; i<4; i++) _global_ground[i] = global_ground[i];
 }
 
-void Rotor::setParameter(char *parametername, float value)
+void Rotor::setParameter(const char *parametername, float value)
 {
 #define p(a,b) if (strcmp(parametername,#a)==0) _##a = (value * (b)); else
     p(translift_ve,1)
@@ -680,6 +747,27 @@ void Rotorgear::setRotorBrake(float lval)
     _rotorbrake=lval;
 }
 
+void Rotor::setTiltYaw(float lval)
+{
+    lval = Math::clamp(lval, -1, 1);
+    _tilt_yaw = _min_tilt_yaw+(lval+1)/2*(_max_tilt_yaw-_min_tilt_yaw);
+    _directions_and_postions_dirty = true;
+}
+
+void Rotor::setTiltPitch(float lval)
+{
+    lval = Math::clamp(lval, -1, 1);
+    _tilt_pitch = _min_tilt_pitch+(lval+1)/2*(_max_tilt_pitch-_min_tilt_pitch);
+    _directions_and_postions_dirty = true;
+}
+
+void Rotor::setTiltRoll(float lval)
+{
+    lval = Math::clamp(lval, -1, 1);
+    _tilt_roll = _min_tilt_roll+(lval+1)/2*(_max_tilt_roll-_min_tilt_roll);
+    _directions_and_postions_dirty = true;
+}
+
 void Rotor::setCollective(float lval)
 {
     lval = Math::clamp(lval, -1, 1);
@@ -703,6 +791,12 @@ void Rotor::setCyclicail(float lval,float rval)
     _cyclicail=-(_mincyclicail+(lval+1)/2*(_maxcyclicail-_mincyclicail));
 }
 
+void Rotor::setRotorBalance(float lval)
+{
+    lval = Math::clamp(lval, -1, 1);
+    _balance2 = lval;
+}
+
 void Rotor::getPosition(float* out)
 {
     int i;
@@ -724,7 +818,7 @@ void Rotor::calcLiftFactor(float* v, float rho, State *s)
     _f_ge=1+_diameter/_ground_effect_altitude*_ground_effect_constant;
 
     // Now calculate translational lift
-    float v_vert = Math::dot3(v,_normal);
+    // float v_vert = Math::dot3(v,_normal);
     float help[3];
     Math::cross3(v,_normal,help);
     float v_horiz = Math::mag3(help);
@@ -735,6 +829,7 @@ void Rotor::calcLiftFactor(float* v, float rho, State *s)
 
     //store the gravity direction
     Glue::geodUp(s->pos, _grav_direction);
+    s->velGlobalToLocal(_grav_direction, _grav_direction);
 }
 
 void Rotor::findGroundEffectAltitude(Ground * ground_cb,State *s)
@@ -937,27 +1032,45 @@ void Rotor::getDownWash(float *pos, float *v_heli, float *downwash)
     //at dist = rotor radius it is assumed to be 1/e * v1 + (1-1/e)* v2
 
     float v = g * v1 + (1-g) * v2;
-    Math::mul3(-v,_normal_with_yaw_roll,downwash);
+    Math::mul3(-v*_downwash_factor,_normal_with_yaw_roll,downwash);
     //the downwash is calculated in the opposite direction of the normal
 }
 
-void Rotor::compile()
+void Rotor::euler2orient(float roll, float pitch, float hdg, float* out)
 {
-    // Have we already been compiled?
-    if(_rotorparts.size() != 0) return;
+    // the Glue::euler2orient, inverts y<z due to different bases
+    // therefore the negation of all "y" and "z" coeffizients
+    Glue::euler2orient(roll,pitch,hdg,out);
+    for (int i=3;i<9;i++) out[i]*=-1.0;
+}
 
-    //rotor is divided into _number_of_parts parts
-    //each part is calcualted at _number_of_segments points
 
-    //clamp to 4..256
-    //and make it a factor of 4
-    _number_of_parts=(int(Math::clamp(_number_of_parts,4,256))>>2)<<2;
-
-    _dynamic=_dynamic*(1/                          //inverse of the time
-        ( (60/_rotor_rpm)/4         //for rotating 90 deg
-        +(60/_rotor_rpm)/(2*_number_of_blades) //+ meantime a rotorblade 
-                                               //will pass a given point 
-        ));
+void Rotor::updateDirectionsAndPositions(float *rot)
+{
+    if (!_directions_and_postions_dirty)
+    {
+        rot[0]=rot[1]=rot[2]=0;
+        return;
+    }
+    rot[0]=_old_tilt_roll-_tilt_roll;
+    rot[1]=_old_tilt_pitch-_tilt_pitch;
+    rot[2]=_old_tilt_yaw-_tilt_yaw;
+    _old_tilt_roll=_tilt_roll;
+    _old_tilt_pitch=_tilt_pitch;
+    _old_tilt_yaw=_tilt_yaw;
+    float orient[9];
+    euler2orient(_tilt_roll, _tilt_pitch, _tilt_yaw, orient);
+    float forward[3];
+    float normal[3];
+    float base[3];
+    Math::sub3(_base,_tilt_center,base);
+    Math::vmul33(orient, base, base);
+    Math::add3(base,_tilt_center,base);
+    Math::vmul33(orient, _forward, forward);
+    Math::vmul33(orient, _normal, normal);
+#define _base base
+#define _forward forward
+#define _normal normal
     float directions[5][3];
     //pointing forward, right, ... the 5th is ony for calculation
     directions[0][0]=_forward[0];
@@ -970,18 +1083,17 @@ void Rotor::compile()
             Math::cross3(directions[i-1],_normal,directions[i]);
         else
             Math::cross3(_normal,directions[i-1],directions[i]);
-        Math::unit3(directions[i],directions[i]);
     }
     Math::set3(directions[4],directions[0]);
     // now directions[0] is perpendicular to the _normal.and has a length
     // of 1. if _forward is already normalized and perpendicular to the 
     // normal, directions[0] will be the same
-    _num_ground_contact_pos=(_number_of_parts<16)?_number_of_parts:16;
+    //_num_ground_contact_pos=(_number_of_parts<16)?_number_of_parts:16;
     for (i=0;i<_num_ground_contact_pos;i++)
     {
         float help[3];
-        float s = Math::sin(pi*2*_num_ground_contact_pos/i);
-        float c = Math::cos(pi*2*_num_ground_contact_pos/i);
+        float s = Math::sin(pi*2*i/_num_ground_contact_pos);
+        float c = Math::cos(pi*2*i/_num_ground_contact_pos);
         Math::mul3(c*_diameter*0.5,directions[0],_ground_contact_pos[i]);
         Math::mul3(s*_diameter*0.5,directions[1],help);
         Math::add3(help,_ground_contact_pos[i],_ground_contact_pos[i]);
@@ -992,6 +1104,76 @@ void Rotor::compile()
         Math::mul3(_diameter*0.7,directions[i],_groundeffectpos[i]);
         Math::add3(_base,_groundeffectpos[i],_groundeffectpos[i]);
     }
+    for (i=0;i<_number_of_parts;i++)
+    {
+        Rotorpart* rp = getRotorpart(i);
+        float lpos[3],lforceattac[3],lspeed[3],dirzentforce[3];
+        float s = Math::sin(2*pi*i/_number_of_parts);
+        float c = Math::cos(2*pi*i/_number_of_parts);
+        float sp = Math::sin(float(2*pi*i/_number_of_parts-pi/2.+_phi));
+        float cp = Math::cos(float(2*pi*i/_number_of_parts-pi/2.+_phi));
+        float direction[3],nextdirection[3],help[3],direction90deg[3];
+        float rotorpartmass = _weight_per_blade*_number_of_blades/_number_of_parts*.453;
+        float speed=_rotor_rpm/60*_diameter*_rel_blade_center*pi;
+        float lentocenter=_diameter*_rel_blade_center*0.5;
+        float lentoforceattac=_diameter*_rel_len_hinge*0.5;
+        float zentforce=rotorpartmass*speed*speed/lentocenter;
+    
+        Math::mul3(c ,directions[0],help);
+        Math::mul3(s ,directions[1],direction);
+        Math::add3(help,direction,direction);
+
+        Math::mul3(c ,directions[1],help);
+        Math::mul3(s ,directions[2],direction90deg);
+        Math::add3(help,direction90deg,direction90deg);
+        
+        Math::mul3(cp ,directions[1],help);
+        Math::mul3(sp ,directions[2],nextdirection);
+        Math::add3(help,nextdirection,nextdirection);
+
+        Math::mul3(lentocenter,direction,lpos);
+        Math::add3(lpos,_base,lpos);
+        Math::mul3(lentoforceattac,nextdirection,lforceattac);
+        //nextdirection: +90deg (gyro)!!!
+
+        Math::add3(lforceattac,_base,lforceattac);
+        Math::mul3(speed,direction90deg,lspeed);
+        Math::mul3(1,nextdirection,dirzentforce);
+        rp->setPosition(lpos);
+        rp->setNormal(_normal);
+        rp->setZentipetalForce(zentforce);
+        rp->setPositionForceAttac(lforceattac);
+        rp->setSpeed(lspeed);
+        rp->setDirectionofZentipetalforce(dirzentforce);
+        rp->setDirectionofRotorPart(direction);
+    }
+#undef _base
+#undef _forward
+#undef _normal
+    _directions_and_postions_dirty=false;
+}
+
+void Rotor::compile()
+{
+    // Have we already been compiled?
+    if(_rotorparts.size() != 0) return;
+
+    //rotor is divided into _number_of_parts parts
+    //each part is calcualted at _number_of_segments points
+
+    //clamp to 4..256
+    //and make it a factor of 4
+    _number_of_parts=(int(Math::clamp(_number_of_parts,4,256))>>2)<<2;
+
+    _dynamic=_dynamic*(1/                          //inverse of the time
+        ( (60/_rotor_rpm)/4         //for rotating 90 deg
+        +(60/_rotor_rpm)/(2*_number_of_blades) //+ meantime a rotorblade 
+                                               //will pass a given point 
+        ));
+    //normalize the directions
+    Math::unit3(_forward,_forward);
+    Math::unit3(_normal,_normal);
+    _num_ground_contact_pos=(_number_of_parts<16)?_number_of_parts:16;
     float rotorpartmass = _weight_per_blade*_number_of_blades/_number_of_parts*.453;
     //was pounds -> now kg
 
@@ -999,7 +1181,7 @@ void Rotor::compile()
         * _diameter * _rel_blade_center * _rel_blade_center /(0.5*0.5);
     float speed=_rotor_rpm/60*_diameter*_rel_blade_center*pi;
     float lentocenter=_diameter*_rel_blade_center*0.5;
-    float lentoforceattac=_diameter*_rel_len_hinge*0.5;
+    // float lentoforceattac=_diameter*_rel_len_hinge*0.5;
     float zentforce=rotorpartmass*speed*speed/lentocenter;
     float pitchaforce=_force_at_pitch_a/_number_of_parts*.453*9.81;
     // was pounds of force, now N, devided by _number_of_parts
@@ -1014,8 +1196,8 @@ void Rotor::compile()
 
     float relamp=(omega*omega/(2*_delta*Math::sqrt(sqr(omega0*omega0-omega*omega)
         +4*_delta*_delta*omega*omega)))*_cyclic_factor;
-    float relamp_theoretical=(omega*omega/(2*delta_theoretical*Math::sqrt(sqr(omega0*omega0-omega*omega)
-        +4*delta_theoretical*delta_theoretical*omega*omega)))*_cyclic_factor;
+    //float relamp_theoretical=(omega*omega/(2*delta_theoretical*Math::sqrt(sqr(omega0*omega0-omega*omega)
+    //    +4*delta_theoretical*delta_theoretical*omega*omega)))*_cyclic_factor;
     _phi=Math::acos(_rel_len_hinge);
     _phi-=Math::atan(_delta3);
     if (!_no_torque)
@@ -1034,37 +1216,10 @@ void Rotor::compile()
     }
 
     Rotorpart* rps[256];
+    int i;
     for (i=0;i<_number_of_parts;i++)
     {
-        float lpos[3],lforceattac[3],lspeed[3],dirzentforce[3];
-        float s = Math::sin(2*pi*i/_number_of_parts);
-        float c = Math::cos(2*pi*i/_number_of_parts);
-        float sp = Math::sin(float(2*pi*i/_number_of_parts-pi/2.+_phi));
-        float cp = Math::cos(float(2*pi*i/_number_of_parts-pi/2.+_phi));
-        float direction[3],nextdirection[3],help[3],direction90deg[3];
-        Math::mul3(c ,directions[0],help);
-        Math::mul3(s ,directions[1],direction);
-        Math::add3(help,direction,direction);
-
-        Math::mul3(c ,directions[1],help);
-        Math::mul3(s ,directions[2],direction90deg);
-        Math::add3(help,direction90deg,direction90deg);
-        
-        Math::mul3(cp ,directions[1],help);
-        Math::mul3(sp ,directions[2],nextdirection);
-        Math::add3(help,nextdirection,nextdirection);
-
-        Math::mul3(lentocenter,direction,lpos);
-        Math::add3(lpos,_base,lpos);
-        Math::mul3(lentoforceattac,nextdirection,lforceattac);
-        //nextdirection: +90deg (gyro)!!!
-
-        Math::add3(lforceattac,_base,lforceattac);
-        Math::mul3(speed,direction90deg,lspeed);
-        Math::mul3(1,nextdirection,dirzentforce);
-
-        Rotorpart* rp=rps[i]=newRotorpart(lpos, lforceattac, _normal,
-            lspeed,dirzentforce,zentforce,pitchaforce,_delta3,rotorpartmass,
+        Rotorpart* rp=rps[i]=newRotorpart(zentforce,pitchaforce,_delta3,rotorpartmass,
             _translift,_rel_len_hinge,lentocenter);
         int k = i*4/_number_of_parts;
         rp->setAlphaoutput(_alphaoutput[k&1?k:(_ccw?k^2:k)],0);
@@ -1072,7 +1227,6 @@ void Rotor::compile()
         _rotorparts.add(rp);
         rp->setTorque(torquemax,torque0);
         rp->setRelamp(relamp);
-        rp->setDirectionofRotorPart(direction);
         rp->setTorqueOfInertia(_torque_of_inertia/_number_of_parts);
         rp->setDirection(2*pi*i/_number_of_parts);
     }
@@ -1084,6 +1238,8 @@ void Rotor::compile()
             rps[(i-_number_of_parts/4+_number_of_parts)%_number_of_parts],
             rps[(i+_number_of_parts/4)%_number_of_parts]);
     }
+    float drot[3];
+    updateDirectionsAndPositions(drot);
     for (i=0;i<_number_of_parts;i++)
     {
         rps[i]->setCompiled();
@@ -1177,6 +1333,10 @@ void Rotor::compile()
         rps[i]->setRelamp(relamp);
     }
     rps[0]->setOmega(0);
+    setCollective(0);
+    setCyclicail(0,0);
+    setCyclicele(0,0);
+
     writeInfo();
 
     //tie the properties
@@ -1294,17 +1454,10 @@ void Rotor:: writeInfo()
     }
 #endif
 }
-Rotorpart* Rotor::newRotorpart(float* pos, float *posforceattac, float *normal,
-    float* speed,float *dirzentforce, float zentforce,float maxpitchforce,
+Rotorpart* Rotor::newRotorpart(float zentforce,float maxpitchforce,
     float delta3,float mass,float translift,float rellenhinge,float len)
 {
     Rotorpart *r = new Rotorpart();
-    r->setPosition(pos);
-    r->setNormal(normal);
-    r->setZentipetalForce(zentforce);
-    r->setPositionForceAttac(posforceattac);
-    r->setSpeed(speed);
-    r->setDirectionofZentipetalforce(dirzentforce);
     r->setDelta3(delta3);
     r->setDynamic(_dynamic);
     r->setTranslift(_translift);
@@ -1375,16 +1528,14 @@ void Rotorgear::calcForces(float* torqueOut)
             total_torque+=r->getTorque()*omegan;
         }
         float max_torque_of_engine=0;
-        SGPropertyNode * node=fgGetNode("/rotors/gear", true);
-        float target_rel_rpm=node->getDoubleValue("target-rel-rpm",1);
+        // SGPropertyNode * node=fgGetNode("/rotors/gear", true);
         if (_engineon)
         {
-            float max_rel_torque=node->getDoubleValue("max-rel-torque",1);
-            max_torque_of_engine=_max_power_engine*max_rel_torque;
-            float df=target_rel_rpm-omegarel;
+            max_torque_of_engine=_max_power_engine*_max_rel_torque;
+            float df=_target_rel_rpm-omegarel;
             df/=_engine_prop_factor;
             df = Math::clamp(df, 0, 1);
-            max_torque_of_engine = df * _max_power_engine*max_rel_torque;
+            max_torque_of_engine = df * _max_power_engine*_max_rel_torque;
         }
         total_torque*=-1;
         _ddt_omegarel=0;
@@ -1411,7 +1562,7 @@ void Rotorgear::calcForces(float* torqueOut)
 
         //change the rotation of the rotors 
         if ((max_torque_of_engine<total_torque) //decreasing rotation
-            ||((max_torque_of_engine>total_torque)&&(omegarel<target_rel_rpm))
+            ||((max_torque_of_engine>total_torque)&&(omegarel<_target_rel_rpm))
             //increasing rotation due to engine
             ||(total_torque<0) ) //increasing rotation due to autorotation
         {
@@ -1448,7 +1599,7 @@ void Rotorgear::calcForces(float* torqueOut)
             for(j=0; j<_rotors.size(); j++) {
                 Rotor* r = (Rotor*)_rotors.get(j);
                 for(i=0; i<r->_rotorparts.size(); i++) {
-                    float torque_scalar=0;
+                    // float torque_scalar=0;
                     Rotorpart* rp = (Rotorpart*)r->_rotorparts.get(i);
                     float torque[3];
                     rp->getAccelTorque(_ddt_omegarel,torque);
@@ -1468,13 +1619,11 @@ void Rotorgear::addRotor(Rotor* rotor)
 
 void Rotorgear::compile()
 {
-    float wgt = 0;
+    // float wgt = 0;
     for(int j=0; j<_rotors.size(); j++) {
         Rotor* r = (Rotor*)_rotors.get(j);
         r->compile();
     }
-    fgGetNode("/rotors/gear/target-rel-rpm", true)->setDoubleValue(1);
-    fgGetNode("/rotors/gear/max-rel-torque", true)->setDoubleValue(1);
 }
 
 void Rotorgear::getDownWash(float *pos, float * v_heli, float *downwash)
@@ -1526,6 +1675,8 @@ Rotorgear::Rotorgear()
     _ddt_omegarel=0;
     _engine_accel_limit=0.05f;
     _total_torque_on_engine=0;
+    _target_rel_rpm=1;
+    _max_rel_torque=1;
 }
 
 Rotorgear::~Rotorgear()