SITL: fixed airspeed pass-thru from simulators

This commit is contained in:
Andrew Tridgell 2015-05-23 11:24:10 +10:00
parent e7f3716e8c
commit da5d5c9936
7 changed files with 15 additions and 1 deletions

View File

@ -233,7 +233,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) const
fdm.rollDeg = degrees(r); fdm.rollDeg = degrees(r);
fdm.pitchDeg = degrees(p); fdm.pitchDeg = degrees(p);
fdm.yawDeg = degrees(y); fdm.yawDeg = degrees(y);
fdm.airspeed = velocity_ef.length(); fdm.airspeed = airspeed;
fdm.magic = 0x4c56414f; fdm.magic = 0x4c56414f;
} }

View File

@ -77,6 +77,7 @@ protected:
Vector3f position; // meters, NED from origin Vector3f position; // meters, NED from origin
float mass; // kg float mass; // kg
Vector3f accel_body; // m/s/s NED, body frame Vector3f accel_body; // m/s/s NED, body frame
float airspeed; // m/s, apparent airspeed
uint64_t time_now_us; uint64_t time_now_us;

View File

@ -129,6 +129,9 @@ void CRRCSim::recv_fdm(const struct sitl_input &input)
position.y = posdelta.y; position.y = posdelta.y;
position.z = -pkt.altitude; position.z = -pkt.altitude;
// assume zero wind for now
airspeed = velocity_ef.length();
dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw); dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
// auto-adjust to crrcsim frame rate // auto-adjust to crrcsim frame rate

View File

@ -131,6 +131,9 @@ void Helicopter::update(const struct sitl_input &input)
Vector3f old_position = position; Vector3f old_position = position;
position += velocity_ef * delta_time; position += velocity_ef * delta_time;
// assume zero wind for now
airspeed = velocity_ef.length();
// constrain height to the ground // constrain height to the ground
if (on_ground(position)) { if (on_ground(position)) {
if (!on_ground(old_position)) { if (!on_ground(old_position)) {

View File

@ -405,6 +405,7 @@ void JSBSim::recv_fdm(const struct sitl_input &input)
location.lng = degrees(fdm.longitude) * 1.0e7; location.lng = degrees(fdm.longitude) * 1.0e7;
location.alt = fdm.agl*100 + home.alt; location.alt = fdm.agl*100 + home.alt;
dcm.from_euler(fdm.phi, fdm.theta, fdm.psi); dcm.from_euler(fdm.phi, fdm.theta, fdm.psi);
airspeed = fdm.vcas * FEET_TO_METERS;
// assume 1kHz for now // assume 1kHz for now
time_now_us += 1000; time_now_us += 1000;

View File

@ -204,6 +204,9 @@ void MultiCopter::update(const struct sitl_input &input)
Vector3f old_position = position; Vector3f old_position = position;
position += velocity_ef * delta_time; position += velocity_ef * delta_time;
// assume zero wind for now
airspeed = velocity_ef.length();
// constrain height to the ground // constrain height to the ground
if (on_ground(position)) { if (on_ground(position)) {
if (!on_ground(old_position)) { if (!on_ground(old_position)) {

View File

@ -107,6 +107,9 @@ void last_letter::recv_fdm(const struct sitl_input &input)
location.alt = pkt.altitude*1.0e2; location.alt = pkt.altitude*1.0e2;
dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw); 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 // auto-adjust to last_letter frame rate
uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us; uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us;
time_now_us += deltat_us; time_now_us += deltat_us;