mirror of https://github.com/ArduPilot/ardupilot
SITL: improve airspeed in FlightAxis for RF8
use 3D wind to get airspeed along X axis of aircraft
This commit is contained in:
parent
cc679db55b
commit
ac7e969aae
|
@ -450,7 +450,26 @@ void FlightAxis::update(const struct sitl_input &input)
|
|||
position -= position_offset;
|
||||
|
||||
airspeed = state.m_airspeed_MPS;
|
||||
airspeed_pitot = state.m_airspeed_MPS;
|
||||
|
||||
/* for pitot airspeed we need the airspeed along the X axis. We
|
||||
can't get that from m_airspeed_MPS, so instead we canculate it
|
||||
from wind vector and ground speed
|
||||
*/
|
||||
Vector3f m_wind_ef(-state.m_windY_MPS,-state.m_windX_MPS,-state.m_windZ_MPS);
|
||||
Vector3f airspeed_3d_ef = m_wind_ef + velocity_ef;
|
||||
Vector3f airspeed3d = dcm.mul_transpose(airspeed_3d_ef);
|
||||
|
||||
airspeed_pitot = MAX(airspeed3d.x,0);
|
||||
|
||||
#if 0
|
||||
printf("WIND: %.1f %.1f %.1f AS3D %.1f %.1f %.1f\n",
|
||||
state.m_windX_MPS,
|
||||
state.m_windY_MPS,
|
||||
state.m_windZ_MPS,
|
||||
airspeed3d.x,
|
||||
airspeed3d.y,
|
||||
airspeed3d.z);
|
||||
#endif
|
||||
|
||||
battery_voltage = state.m_batteryVoltage_VOLTS;
|
||||
battery_current = state.m_batteryCurrentDraw_AMPS;
|
||||
|
|
Loading…
Reference in New Issue