From fb8595999f253f9a4ad873596da49703f84b4840 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 26 Apr 2013 17:43:36 +0200 Subject: [PATCH] Fixed state HIL, fixed sensor HIL XPlane x direction velocity vector --- src/comm/QGCXPlaneLink.cc | 4 ++-- src/uas/UAS.cc | 7 +++++-- src/uas/UAS.h | 1 + 3 files changed, 8 insertions(+), 4 deletions(-) diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index cb5bf335f..a695cb7c4 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -567,8 +567,8 @@ void QGCXPlaneLink::readBytes() } else if (p.index == 21 && xPlaneVersion == 10) { - vx = p.f[3]; - vy = -p.f[5]; + vy = p.f[3]; + vx = -p.f[5]; vz = p.f[4]; } else if (p.index == 12) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 69a8805d5..a1d85cc31 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -112,7 +112,9 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), lastNonNullTime(0), onboardTimeOffsetInvalidCount(0), hilEnabled(false), - lastSendTimeGPS(0) + sensorHil(false), + lastSendTimeGPS(0), + lastSendTimeSensors(0) { for (unsigned int i = 0; i<255;++i) @@ -2733,7 +2735,7 @@ void UAS::sendHilState(uint64_t time_us, float roll, float pitch, float yaw, flo { if (this->mode & MAV_MODE_FLAG_HIL_ENABLED) { - if (sensorHil) { + if (QGC::groundTimeMilliseconds() - lastSendTimeSensors < 100) { // Emit attitude for cross-check emit attitudeChanged(this, 201, roll, pitch, yaw, getUnixTime()); emit valueChanged(uasId, "roll sim", "rad", roll, getUnixTime()); @@ -2777,6 +2779,7 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl fields_changed); sendMessage(msg); sensorHil = true; + lastSendTimeSensors = QGC::groundTimeMilliseconds(); } else { diff --git a/src/uas/UAS.h b/src/uas/UAS.h index c13e85560..bfb02bf70 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -716,6 +716,7 @@ protected: bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting) bool sensorHil; ///< True if sensor HIL is enabled quint64 lastSendTimeGPS; ///< Last HIL GPS message sent + quint64 lastSendTimeSensors; protected slots: /** @brief Write settings to disk */ -- 2.22.0