considering u,v,wbody-fps are the ECEF velocity expressed in body axis, change in all functions/variables name dealing with them, wrongly named with wind, or even north, east, down.
This commit is contained in:
parent
d127f7709f
commit
ecfdf354f1
14 changed files with 79 additions and 79 deletions
|
@ -470,9 +470,9 @@ void FGExternalPipe::process_set_command( const string_list &tokens ) {
|
|||
_set_Velocities_Local( net->v_north,
|
||||
net->v_east,
|
||||
net->v_down );
|
||||
_set_Velocities_Wind_Body( net->v_wind_body_north,
|
||||
net->v_wind_body_east,
|
||||
net->v_wind_body_down );
|
||||
_set_Velocities_Body( net->v_body_u,
|
||||
net->v_body_v,
|
||||
net->v_body_w );
|
||||
|
||||
_set_Accels_Pilot_Body( net->A_X_pilot,
|
||||
net->A_Y_pilot,
|
||||
|
|
|
@ -760,9 +760,9 @@ bool FGJSBsim::copy_from_JSBsim()
|
|||
Propagate->GetVel(FGJSBBase::eEast),
|
||||
Propagate->GetVel(FGJSBBase::eDown) );
|
||||
|
||||
_set_Velocities_Wind_Body( Propagate->GetUVW(1),
|
||||
Propagate->GetUVW(2),
|
||||
Propagate->GetUVW(3) );
|
||||
_set_Velocities_Body( Propagate->GetUVW(1),
|
||||
Propagate->GetUVW(2),
|
||||
Propagate->GetUVW(3) );
|
||||
|
||||
// Make the HUD work ...
|
||||
_set_Velocities_Ground( Propagate->GetVel(FGJSBBase::eNorth),
|
||||
|
@ -1124,9 +1124,9 @@ void FGJSBsim::set_Velocities_Local( double north, double east, double down )
|
|||
FGInterface::set_Velocities_Local(north, east, down);
|
||||
}
|
||||
|
||||
void FGJSBsim::set_Velocities_Wind_Body( double u, double v, double w)
|
||||
void FGJSBsim::set_Velocities_Body( double u, double v, double w)
|
||||
{
|
||||
SG_LOG(SG_FLIGHT,SG_INFO, "FGJSBsim::set_Velocities_Wind_Body: "
|
||||
SG_LOG(SG_FLIGHT,SG_INFO, "FGJSBsim::set_Velocities_Body: "
|
||||
<< u << ", " << v << ", " << w );
|
||||
|
||||
if (needTrim) {
|
||||
|
@ -1140,7 +1140,7 @@ void FGJSBsim::set_Velocities_Wind_Body( double u, double v, double w)
|
|||
Propagate->SetUVW(3, w);
|
||||
}
|
||||
|
||||
FGInterface::set_Velocities_Wind_Body(u, v, w);
|
||||
FGInterface::set_Velocities_Body(u, v, w);
|
||||
}
|
||||
|
||||
//Euler angles
|
||||
|
|
|
@ -166,7 +166,7 @@ public:
|
|||
@param u X velocity in ft/sec
|
||||
@param v Y velocity in ft/sec
|
||||
@param w Z velocity in ft/sec */
|
||||
void set_Velocities_Wind_Body( double u, double v, double w);
|
||||
void set_Velocities_Body( double u, double v, double w);
|
||||
//@}
|
||||
|
||||
/** Euler Angle Parameter Set
|
||||
|
|
|
@ -653,7 +653,7 @@ bool FGLaRCsim::copy_from_LaRCsim() {
|
|||
// set_Velocities_Local_Rel_Airmass( V_north_rel_airmass,
|
||||
// V_east_rel_airmass, V_down_rel_airmass );
|
||||
// set_Velocities_Gust( U_gust, V_gust, W_gust );
|
||||
_set_Velocities_Wind_Body( U_body, V_body, W_body );
|
||||
_set_Velocities_Body( U_body, V_body, W_body );
|
||||
|
||||
_set_V_rel_wind( V_rel_wind );
|
||||
// set_V_true_kts( V_true_kts );
|
||||
|
@ -865,8 +865,8 @@ void FGLaRCsim::set_Velocities_Local( double north, double east, double down ){
|
|||
copy_from_LaRCsim(); //update the bus
|
||||
}
|
||||
|
||||
void FGLaRCsim::set_Velocities_Wind_Body( double u, double v, double w){
|
||||
SG_LOG( SG_FLIGHT, SG_INFO, "FGLaRCsim::set_Velocities_Wind_Body: "
|
||||
void FGLaRCsim::set_Velocities_Body( double u, double v, double w){
|
||||
SG_LOG( SG_FLIGHT, SG_INFO, "FGLaRCsim::set_Velocities_Body: "
|
||||
<< u << " " << v << " " << w );
|
||||
snap_shot();
|
||||
lsic->SetUVWFpsIC(u,v,w);
|
||||
|
|
|
@ -396,7 +396,7 @@ void YASim::copyToYASim(bool copyState)
|
|||
// _set_Accels_CG_Body_N
|
||||
// _set_Velocities_Local
|
||||
// _set_Velocities_Ground
|
||||
// _set_Velocities_Wind_Body
|
||||
// _set_Velocities_Body
|
||||
// _set_Omega_Body
|
||||
// _set_Euler_Rates
|
||||
// _set_Euler_Angles
|
||||
|
@ -469,6 +469,10 @@ void YASim::copyFromYASim()
|
|||
|
||||
// _set_Geocentric_Rates(M2FT*v[0], M2FT*v[1], M2FT*v[2]); // UNUSED
|
||||
|
||||
// ecef speed in body axis
|
||||
Math::vmul33(s->orient, s->v, v);
|
||||
_set_Velocities_Body(v[0]*M2FT, -v[1]*M2FT, -v[2]*M2FT);
|
||||
|
||||
// Airflow velocity.
|
||||
float wind[3];
|
||||
wind[0] = get_V_north_airmass() * FT2M * -1.0; // Wind in NED
|
||||
|
@ -477,7 +481,6 @@ void YASim::copyFromYASim()
|
|||
Math::tmul33(xyz2ned, wind, wind); // Wind in global
|
||||
Math::sub3(s->v, wind, v); // V - wind in global
|
||||
Math::vmul33(s->orient, v, v); // to body coordinates
|
||||
_set_Velocities_Wind_Body(v[0]*M2FT, -v[1]*M2FT, -v[2]*M2FT);
|
||||
_set_V_rel_wind(Math::mag3(v)*M2FT); // units?
|
||||
|
||||
float P = _pressure_inhg->getFloatValue() * INHG2PA;
|
||||
|
|
|
@ -98,7 +98,7 @@ FGInterface::_setup ()
|
|||
_state.v_local_v = SGVec3d::zeros();
|
||||
_state.v_local_rel_ground_v = SGVec3d::zeros();
|
||||
_state.v_local_airmass_v = SGVec3d::zeros();
|
||||
_state.v_wind_body_v = SGVec3d::zeros();
|
||||
_state.v_body_v = SGVec3d::zeros();
|
||||
_state.omega_body_v = SGVec3d::zeros();
|
||||
_state.euler_rates_v = SGVec3d::zeros();
|
||||
_state.geocentric_rates_v = SGVec3d::zeros();
|
||||
|
@ -206,7 +206,7 @@ FGInterface::common_init ()
|
|||
} else if ( speedset == "mach" || speedset == "MACH" ) {
|
||||
set_Mach_number( fgGetDouble("/sim/presets/mach") );
|
||||
} else if ( speedset == "UVW" || speedset == "uvw" ) {
|
||||
set_Velocities_Wind_Body(
|
||||
set_Velocities_Body(
|
||||
fgGetDouble("/sim/presets/uBody-fps"),
|
||||
fgGetDouble("/sim/presets/vBody-fps"),
|
||||
fgGetDouble("/sim/presets/wBody-fps") );
|
||||
|
@ -366,7 +366,7 @@ FGInterface::bind ()
|
|||
_tiedProperties.Tie("/velocities/down-relground-fps", this,
|
||||
&FGInterface::get_V_down_rel_ground); // read-only
|
||||
|
||||
// Relative wind
|
||||
// ECEF velocity in body axis
|
||||
// FIXME: temporarily archivable, until the NED problem is fixed.
|
||||
_tiedProperties.Tie("/velocities/uBody-fps", this,
|
||||
&FGInterface::get_uBody,
|
||||
|
@ -565,12 +565,12 @@ void FGInterface::set_Velocities_Local( double north,
|
|||
_state.v_local_v[2] = down;
|
||||
}
|
||||
|
||||
void FGInterface::set_Velocities_Wind_Body( double u,
|
||||
void FGInterface::set_Velocities_Body( double u,
|
||||
double v,
|
||||
double w){
|
||||
_state.v_wind_body_v[0] = u;
|
||||
_state.v_wind_body_v[1] = v;
|
||||
_state.v_wind_body_v[2] = w;
|
||||
_state.v_body_v[0] = u;
|
||||
_state.v_body_v[1] = v;
|
||||
_state.v_body_v[2] = w;
|
||||
}
|
||||
|
||||
// Euler angles
|
||||
|
@ -615,7 +615,7 @@ void FGInterface::_busdump(void)
|
|||
SG_LOG(SG_FLIGHT,SG_INFO,"v_local_v: " << _state.v_local_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"v_local_rel_ground_v: " << _state.v_local_rel_ground_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"v_local_airmass_v: " << _state.v_local_airmass_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"v_wind_body_v: " << _state.v_wind_body_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"v_body_v: " << _state.v_body_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"omega_body_v: " << _state.omega_body_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"euler_rates_v: " << _state.euler_rates_v);
|
||||
SG_LOG(SG_FLIGHT,SG_INFO,"geocentric_rates_v: " << _state.geocentric_rates_v);
|
||||
|
|
|
@ -162,7 +162,7 @@ private:
|
|||
SGVec3d v_local_v;
|
||||
SGVec3d v_local_rel_ground_v; // V rel w.r.t. earth surface
|
||||
SGVec3d v_local_airmass_v; // velocity of airmass (steady winds)
|
||||
SGVec3d v_wind_body_v; // Wind-relative velocities in body axis
|
||||
SGVec3d v_body_v; // ECEF velocities in body axis
|
||||
|
||||
SGVec3d omega_body_v; // Angular B rates
|
||||
SGVec3d euler_rates_v;
|
||||
|
@ -284,10 +284,10 @@ public:
|
|||
_state.v_local_airmass_v[1] = east;
|
||||
_state.v_local_airmass_v[2] = down;
|
||||
}
|
||||
inline void _set_Velocities_Wind_Body( double u, double v, double w) {
|
||||
_state.v_wind_body_v[0] = u;
|
||||
_state.v_wind_body_v[1] = v;
|
||||
_state.v_wind_body_v[2] = w;
|
||||
inline void _set_Velocities_Body( double u, double v, double w) {
|
||||
_state.v_body_v[0] = u;
|
||||
_state.v_body_v[1] = v;
|
||||
_state.v_body_v[2] = w;
|
||||
}
|
||||
inline void _set_V_rel_wind(double vt) { _state.v_rel_wind = vt; }
|
||||
inline void _set_V_ground_speed( double v) { _state.v_ground_speed = v; }
|
||||
|
@ -456,15 +456,15 @@ public:
|
|||
inline void set_V_down (double down) {
|
||||
set_Velocities_Local(_state.v_local_v[0], _state.v_local_v[1], down);
|
||||
}
|
||||
virtual void set_Velocities_Wind_Body( double u, double v, double w);
|
||||
virtual void set_Velocities_Body( double u, double v, double w);
|
||||
virtual void set_uBody (double uBody) {
|
||||
set_Velocities_Wind_Body(uBody, _state.v_wind_body_v[1], _state.v_wind_body_v[2]);
|
||||
set_Velocities_Body(uBody, _state.v_body_v[1], _state.v_body_v[2]);
|
||||
}
|
||||
virtual void set_vBody (double vBody) {
|
||||
set_Velocities_Wind_Body(_state.v_wind_body_v[0], vBody, _state.v_wind_body_v[2]);
|
||||
set_Velocities_Body(_state.v_body_v[0], vBody, _state.v_body_v[2]);
|
||||
}
|
||||
virtual void set_wBody (double wBody) {
|
||||
set_Velocities_Wind_Body(_state.v_wind_body_v[0], _state.v_wind_body_v[1], wBody);
|
||||
set_Velocities_Body(_state.v_body_v[0], _state.v_body_v[1], wBody);
|
||||
}
|
||||
|
||||
// Euler angles
|
||||
|
@ -538,9 +538,9 @@ public:
|
|||
inline double get_V_north() const { return _state.v_local_v[0]; }
|
||||
inline double get_V_east() const { return _state.v_local_v[1]; }
|
||||
inline double get_V_down() const { return _state.v_local_v[2]; }
|
||||
inline double get_uBody () const { return _state.v_wind_body_v[0]; }
|
||||
inline double get_vBody () const { return _state.v_wind_body_v[1]; }
|
||||
inline double get_wBody () const { return _state.v_wind_body_v[2]; }
|
||||
inline double get_uBody () const { return _state.v_body_v[0]; }
|
||||
inline double get_vBody () const { return _state.v_body_v[1]; }
|
||||
inline double get_wBody () const { return _state.v_body_v[2]; }
|
||||
|
||||
// Please dont comment these out. fdm=ada uses these (see
|
||||
// cockpit.cxx) --->
|
||||
|
@ -559,9 +559,9 @@ public:
|
|||
inline double get_V_east_airmass() const { return _state.v_local_airmass_v[1]; }
|
||||
inline double get_V_down_airmass() const { return _state.v_local_airmass_v[2]; }
|
||||
|
||||
inline double get_U_body() const { return _state.v_wind_body_v[0]; }
|
||||
inline double get_V_body() const { return _state.v_wind_body_v[1]; }
|
||||
inline double get_W_body() const { return _state.v_wind_body_v[2]; }
|
||||
inline double get_U_body() const { return _state.v_body_v[0]; }
|
||||
inline double get_V_body() const { return _state.v_body_v[1]; }
|
||||
inline double get_W_body() const { return _state.v_body_v[2]; }
|
||||
|
||||
inline double get_V_rel_wind() const { return _state.v_rel_wind; }
|
||||
|
||||
|
|
|
@ -266,10 +266,10 @@ void FlightProperties::set_Velocities_Local(double x, double y, double z)
|
|||
_root->setDoubleValue("velocities/speed-down-fps", z);
|
||||
}
|
||||
|
||||
void FlightProperties::set_Velocities_Wind_Body(double x, double y, double z)
|
||||
void FlightProperties::set_Velocities_Body(double x, double y, double z)
|
||||
{
|
||||
_root->setDoubleValue("velocities/vBody-fps", x);
|
||||
_root->setDoubleValue("velocities/uBody-fps", y);
|
||||
_root->setDoubleValue("velocities/uBody-fps", x);
|
||||
_root->setDoubleValue("velocities/vBody-fps", y);
|
||||
_root->setDoubleValue("velocities/wBody-fps", z);
|
||||
}
|
||||
|
||||
|
|
|
@ -119,7 +119,7 @@ public:
|
|||
void set_Climb_Rate(double fps);
|
||||
|
||||
void set_Velocities_Local(double x, double y, double z);
|
||||
void set_Velocities_Wind_Body(double x, double y, double z);
|
||||
void set_Velocities_Body(double x, double y, double z);
|
||||
void set_Accels_Pilot_Body(double x, double y, double z);
|
||||
private:
|
||||
SGPropertyNode* _root;
|
||||
|
|
|
@ -151,9 +151,9 @@ void FGProps2NetFDM( FGNetFDM *net, bool net_byte_order ) {
|
|||
net->v_north = fdm_state.get_V_north();
|
||||
net->v_east = fdm_state.get_V_east();
|
||||
net->v_down = fdm_state.get_V_down();
|
||||
net->v_wind_body_north = fdm_state.get_uBody();
|
||||
net->v_wind_body_east = fdm_state.get_vBody();
|
||||
net->v_wind_body_down = fdm_state.get_wBody();
|
||||
net->v_body_u = fdm_state.get_uBody();
|
||||
net->v_body_v = fdm_state.get_vBody();
|
||||
net->v_body_w = fdm_state.get_wBody();
|
||||
|
||||
net->A_X_pilot = fdm_state.get_A_X_pilot();
|
||||
net->A_Y_pilot = fdm_state.get_A_Y_pilot();
|
||||
|
@ -245,9 +245,9 @@ void FGProps2NetFDM( FGNetFDM *net, bool net_byte_order ) {
|
|||
htonf(net->v_north);
|
||||
htonf(net->v_east);
|
||||
htonf(net->v_down);
|
||||
htonf(net->v_wind_body_north);
|
||||
htonf(net->v_wind_body_east);
|
||||
htonf(net->v_wind_body_down);
|
||||
htonf(net->v_body_u);
|
||||
htonf(net->v_body_v);
|
||||
htonf(net->v_body_w);
|
||||
|
||||
htonf(net->A_X_pilot);
|
||||
htonf(net->A_Y_pilot);
|
||||
|
@ -327,9 +327,9 @@ void FGNetFDM2Props( FGNetFDM *net, bool net_byte_order ) {
|
|||
htonf(net->v_north);
|
||||
htonf(net->v_east);
|
||||
htonf(net->v_down);
|
||||
htonf(net->v_wind_body_north);
|
||||
htonf(net->v_wind_body_east);
|
||||
htonf(net->v_wind_body_down);
|
||||
htonf(net->v_body_u);
|
||||
htonf(net->v_body_v);
|
||||
htonf(net->v_body_w);
|
||||
|
||||
htonf(net->A_X_pilot);
|
||||
htonf(net->A_Y_pilot);
|
||||
|
@ -410,9 +410,9 @@ void FGNetFDM2Props( FGNetFDM *net, bool net_byte_order ) {
|
|||
fdm_state.set_Velocities_Local( net->v_north,
|
||||
net->v_east,
|
||||
net->v_down );
|
||||
fdm_state.set_Velocities_Wind_Body( net->v_wind_body_north,
|
||||
net->v_wind_body_east,
|
||||
net->v_wind_body_down );
|
||||
fdm_state.set_Velocities_Body( net->v_body_u,
|
||||
net->v_body_v,
|
||||
net->v_body_w );
|
||||
|
||||
fdm_state.set_Accels_Pilot_Body( net->A_X_pilot,
|
||||
net->A_Y_pilot,
|
||||
|
|
|
@ -61,12 +61,9 @@ public:
|
|||
float v_north; // north velocity in local/body frame, fps
|
||||
float v_east; // east velocity in local/body frame, fps
|
||||
float v_down; // down/vertical velocity in local/body frame, fps
|
||||
float v_wind_body_north; // north velocity in local/body frame
|
||||
// relative to local airmass, fps
|
||||
float v_wind_body_east; // east velocity in local/body frame
|
||||
// relative to local airmass, fps
|
||||
float v_wind_body_down; // down/vertical velocity in local/body
|
||||
// frame relative to local airmass, fps
|
||||
float v_body_u; // ECEF velocity in body frame
|
||||
float v_body_v; // ECEF velocity in body frame
|
||||
float v_body_w; // ECEF velocity in body frame
|
||||
|
||||
// Accelerations
|
||||
float A_X_pilot; // X accel in body frame ft/sec^2
|
||||
|
|
|
@ -148,9 +148,9 @@ static void midg2fg( const MIDGpos pos, const MIDGatt att,
|
|||
fdm->v_north = 0.0;
|
||||
fdm->v_east = 0.0;
|
||||
fdm->v_down = 0.0;
|
||||
fdm->v_wind_body_north = 0.0;
|
||||
fdm->v_wind_body_east = 0.0;
|
||||
fdm->v_wind_body_down = 0.0;
|
||||
fdm->v_body_u = 0.0;
|
||||
fdm->v_body_v = 0.0;
|
||||
fdm->v_body_w = 0.0;
|
||||
fdm->stall_warning = 0.0;
|
||||
|
||||
fdm->A_X_pilot = 0.0;
|
||||
|
@ -224,9 +224,9 @@ static void midg2fg( const MIDGpos pos, const MIDGatt att,
|
|||
htonf(fdm->v_north);
|
||||
htonf(fdm->v_east);
|
||||
htonf(fdm->v_down);
|
||||
htonf(fdm->v_wind_body_north);
|
||||
htonf(fdm->v_wind_body_east);
|
||||
htonf(fdm->v_wind_body_down);
|
||||
htonf(fdm->v_body_u);
|
||||
htonf(fdm->v_body_v);
|
||||
htonf(fdm->v_body_w);
|
||||
|
||||
htonf(fdm->A_X_pilot);
|
||||
htonf(fdm->A_Y_pilot);
|
||||
|
|
|
@ -210,9 +210,9 @@ static void ugear2fg( gps *gpspacket, imu *imupacket, nav *navpacket,
|
|||
fdm->v_north = 0.0;
|
||||
fdm->v_east = 0.0;
|
||||
fdm->v_down = 0.0;
|
||||
fdm->v_wind_body_north = 0.0;
|
||||
fdm->v_wind_body_east = 0.0;
|
||||
fdm->v_wind_body_down = 0.0;
|
||||
fdm->v_body_u = 0.0;
|
||||
fdm->v_body_v = 0.0;
|
||||
fdm->v_body_w = 0.0;
|
||||
fdm->stall_warning = 0.0;
|
||||
|
||||
fdm->A_X_pilot = 0.0;
|
||||
|
@ -301,9 +301,9 @@ static void ugear2fg( gps *gpspacket, imu *imupacket, nav *navpacket,
|
|||
htonf(fdm->v_north);
|
||||
htonf(fdm->v_east);
|
||||
htonf(fdm->v_down);
|
||||
htonf(fdm->v_wind_body_north);
|
||||
htonf(fdm->v_wind_body_east);
|
||||
htonf(fdm->v_wind_body_down);
|
||||
htonf(fdm->v_body_u);
|
||||
htonf(fdm->v_body_v);
|
||||
htonf(fdm->v_body_w);
|
||||
|
||||
htonf(fdm->A_X_pilot);
|
||||
htonf(fdm->A_Y_pilot);
|
||||
|
|
|
@ -150,9 +150,9 @@ static void gps2fg( const GPSPoint p, FGNetFDM *fdm, FGNetCtrls *ctrls )
|
|||
fdm->v_north = 0.0;
|
||||
fdm->v_east = 0.0;
|
||||
fdm->v_down = 0.0;
|
||||
fdm->v_wind_body_north = 0.0;
|
||||
fdm->v_wind_body_east = 0.0;
|
||||
fdm->v_wind_body_down = 0.0;
|
||||
fdm->v_body_u = 0.0;
|
||||
fdm->v_body_v = 0.0;
|
||||
fdm->v_body_w = 0.0;
|
||||
fdm->stall_warning = 0.0;
|
||||
|
||||
fdm->A_X_pilot = 0.0;
|
||||
|
@ -226,9 +226,9 @@ static void gps2fg( const GPSPoint p, FGNetFDM *fdm, FGNetCtrls *ctrls )
|
|||
htonf(fdm->v_north);
|
||||
htonf(fdm->v_east);
|
||||
htonf(fdm->v_down);
|
||||
htonf(fdm->v_wind_body_north);
|
||||
htonf(fdm->v_wind_body_east);
|
||||
htonf(fdm->v_wind_body_down);
|
||||
htonf(fdm->v_body_u);
|
||||
htonf(fdm->v_body_v);
|
||||
htonf(fdm->v_body_w);
|
||||
|
||||
htonf(fdm->A_X_pilot);
|
||||
htonf(fdm->A_Y_pilot);
|
||||
|
|
Loading…
Reference in a new issue