mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
SITL: fixed airspeed pass-thru from simulators
This commit is contained in:
parent
e7f3716e8c
commit
da5d5c9936
@ -233,7 +233,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) const
|
||||
fdm.rollDeg = degrees(r);
|
||||
fdm.pitchDeg = degrees(p);
|
||||
fdm.yawDeg = degrees(y);
|
||||
fdm.airspeed = velocity_ef.length();
|
||||
fdm.airspeed = airspeed;
|
||||
fdm.magic = 0x4c56414f;
|
||||
}
|
||||
|
||||
|
@ -77,6 +77,7 @@ protected:
|
||||
Vector3f position; // meters, NED from origin
|
||||
float mass; // kg
|
||||
Vector3f accel_body; // m/s/s NED, body frame
|
||||
float airspeed; // m/s, apparent airspeed
|
||||
|
||||
uint64_t time_now_us;
|
||||
|
||||
|
@ -129,6 +129,9 @@ void CRRCSim::recv_fdm(const struct sitl_input &input)
|
||||
position.y = posdelta.y;
|
||||
position.z = -pkt.altitude;
|
||||
|
||||
// assume zero wind for now
|
||||
airspeed = velocity_ef.length();
|
||||
|
||||
dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
|
||||
|
||||
// auto-adjust to crrcsim frame rate
|
||||
|
@ -131,6 +131,9 @@ void Helicopter::update(const struct sitl_input &input)
|
||||
Vector3f old_position = position;
|
||||
position += velocity_ef * delta_time;
|
||||
|
||||
// assume zero wind for now
|
||||
airspeed = velocity_ef.length();
|
||||
|
||||
// constrain height to the ground
|
||||
if (on_ground(position)) {
|
||||
if (!on_ground(old_position)) {
|
||||
|
@ -405,6 +405,7 @@ void JSBSim::recv_fdm(const struct sitl_input &input)
|
||||
location.lng = degrees(fdm.longitude) * 1.0e7;
|
||||
location.alt = fdm.agl*100 + home.alt;
|
||||
dcm.from_euler(fdm.phi, fdm.theta, fdm.psi);
|
||||
airspeed = fdm.vcas * FEET_TO_METERS;
|
||||
|
||||
// assume 1kHz for now
|
||||
time_now_us += 1000;
|
||||
|
@ -204,6 +204,9 @@ void MultiCopter::update(const struct sitl_input &input)
|
||||
Vector3f old_position = position;
|
||||
position += velocity_ef * delta_time;
|
||||
|
||||
// assume zero wind for now
|
||||
airspeed = velocity_ef.length();
|
||||
|
||||
// constrain height to the ground
|
||||
if (on_ground(position)) {
|
||||
if (!on_ground(old_position)) {
|
||||
|
@ -107,6 +107,9 @@ void last_letter::recv_fdm(const struct sitl_input &input)
|
||||
location.alt = pkt.altitude*1.0e2;
|
||||
dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
|
||||
|
||||
// assume zero wind for now
|
||||
airspeed = velocity_ef.length();
|
||||
|
||||
// auto-adjust to last_letter frame rate
|
||||
uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us;
|
||||
time_now_us += deltat_us;
|
||||
|
Loading…
Reference in New Issue
Block a user