diff --git a/.travis.yml b/.travis.yml index 75f8b0e181c2a65052b0e8837f7bc2873bec58b2..37f8ca580b2535cb886f56d319ba9f3f5967ea59 100644 --- a/.travis.yml +++ b/.travis.yml @@ -174,12 +174,14 @@ script: #- ccache -s # unit tests linux/osx - - if [[ "${SPEC}" = "linux-g++-64" && "${CONFIG}" = "debug" ]]; then - mkdir -p ~/.config/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/.config/QtProject/ && - ./debug/QGroundControl --unittest; - elif [[ "${SPEC}" = "macx-clang" && "${CONFIG}" = "debug" ]]; then - mkdir -p ~/Library/Preferences/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/Library/Preferences/QtProject/ && - ./debug/qgroundcontrol.app/Contents/MacOS/QGroundControl --unittest; + - if [ "${TRAVIS_BRANCH}" != "master" ]; then + if [[ "${SPEC}" = "linux-g++-64" && "${CONFIG}" = "debug" ]]; then + mkdir -p ~/.config/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/.config/QtProject/ && + ./debug/QGroundControl --unittest; + elif [[ "${SPEC}" = "macx-clang" && "${CONFIG}" = "debug" ]]; then + mkdir -p ~/Library/Preferences/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/Library/Preferences/QtProject/ && + ./debug/qgroundcontrol.app/Contents/MacOS/QGroundControl --unittest; + fi fi after_success: diff --git a/android/libs/d2xx.jar b/android/libs/d2xx.jar new file mode 100755 index 0000000000000000000000000000000000000000..6610490d14a9a033ec212e5bb7febdd820756146 Binary files /dev/null and b/android/libs/d2xx.jar differ diff --git a/android/res/xml/device_filter.xml b/android/res/xml/device_filter.xml index a149a80b508d8f8978a9fdd66bfedd4b78ca4046..782fae8dd7e17709718b824ace9fa92e9479b52b 100644 --- a/android/res/xml/device_filter.xml +++ b/android/res/xml/device_filter.xml @@ -1,40 +1,6 @@ - + - - - - - - - - - - - - - - - - - - - - diff --git a/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java index ad3627ff38a75a50b71167ddf50f50b4ee5b1b51..5ca03607460a0c38844ebe777bebda38cd0a1f8e 100644 --- a/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java @@ -18,6 +18,10 @@ * Project home page: http://code.google.com/p/usb-serial-for-android/ */ +// IMPORTANT NOTE: +// This code has been modified from the original source. It now uses the FTDI driver provided by +// ftdichip.com to communicate with an FTDI device. The previous code did not work with all FTDI +// devices. package com.hoho.android.usbserial.driver; import android.hardware.usb.UsbConstants; @@ -27,12 +31,16 @@ import android.hardware.usb.UsbEndpoint; import android.hardware.usb.UsbRequest; import android.util.Log; +import com.ftdi.j2xx.D2xxManager; +import com.ftdi.j2xx.FT_Device; import java.io.IOException; import java.nio.ByteBuffer; import java.util.LinkedHashMap; import java.util.Map; +import org.qgroundcontrol.qgchelper.UsbDeviceJNI; + /** * A {@link CommonUsbSerialDriver} implementation for a variety of FTDI devices *

@@ -167,6 +175,8 @@ public class FtdiSerialDriver extends CommonUsbSerialDriver { */ private static final boolean ENABLE_ASYNC_READS = false; + FT_Device m_ftDev; + /** * Filter FTDI status bytes from buffer * @param src The source buffer (which contains status bytes) @@ -219,261 +229,140 @@ public class FtdiSerialDriver extends CommonUsbSerialDriver { @Override public void open() throws IOException { - boolean opened = false; + D2xxManager ftD2xx = null; try { - for (int i = 0; i < mDevice.getInterfaceCount(); i++) { - if (mConnection.claimInterface(mDevice.getInterface(i), true)) { - Log.d(TAG, "claimInterface " + i + " SUCCESS"); - } else { - throw new IOException("Error claiming interface " + i); - } - } - reset(); - opened = true; + ftD2xx = D2xxManager.getInstance(UsbDeviceJNI.m_context); + } catch (D2xxManager.D2xxException ex) { + UsbDeviceJNI.qgcLogDebug("D2xxManager.getInstance threw exception: " + ex.getMessage()); + } + + if (ftD2xx == null) { + String errMsg = "Unable to retrieve D2xxManager instance."; + UsbDeviceJNI.qgcLogWarning(errMsg); + throw new IOException(errMsg); + } + UsbDeviceJNI.qgcLogDebug("Opened D2xxManager"); + + int DevCount = ftD2xx.createDeviceInfoList(UsbDeviceJNI.m_context); + UsbDeviceJNI.qgcLogDebug("Found " + DevCount + " ftdi devices."); + if (DevCount < 1) { + throw new IOException("No FTDI Devices found"); + } + + m_ftDev = null; + try { + m_ftDev = ftD2xx.openByIndex(UsbDeviceJNI.m_context, 0); + } catch (NullPointerException e) { + UsbDeviceJNI.qgcLogDebug("ftD2xx.openByIndex exception: " + e.getMessage()); } finally { - if (!opened) { - close(); + if (m_ftDev == null) { + throw new IOException("No FTDI Devices found"); } } + UsbDeviceJNI.qgcLogDebug("Opened FTDI device."); } @Override public void close() { - mConnection.close(); + if (m_ftDev != null) { + try { + m_ftDev.close(); + } catch (Exception e) { + UsbDeviceJNI.qgcLogWarning("close exception: " + e.getMessage()); + } + m_ftDev = null; + } } @Override public int read(byte[] dest, int timeoutMillis) throws IOException { - final UsbEndpoint endpoint = mDevice.getInterface(0).getEndpoint(0); - - if (ENABLE_ASYNC_READS) { - final int readAmt; - synchronized (mReadBufferLock) { - // mReadBuffer is only used for maximum read size. - readAmt = Math.min(dest.length, mReadBuffer.length); - } - - final UsbRequest request = new UsbRequest(); - request.initialize(mConnection, endpoint); - - final ByteBuffer buf = ByteBuffer.wrap(dest); - if (!request.queue(buf, readAmt)) { - throw new IOException("Error queueing request."); - } - - final UsbRequest response = mConnection.requestWait(); - if (response == null) { - throw new IOException("Null response"); - } - - final int payloadBytesRead = buf.position() - MODEM_STATUS_HEADER_LENGTH; - if (payloadBytesRead > 0) { - return payloadBytesRead; - } else { - return 0; - } - } else { - final int totalBytesRead; - - synchronized (mReadBufferLock) { - final int readAmt = Math.min(dest.length, mReadBuffer.length); - totalBytesRead = mConnection.bulkTransfer(endpoint, mReadBuffer, - readAmt, timeoutMillis); - - if (totalBytesRead < MODEM_STATUS_HEADER_LENGTH) { - throw new IOException("Expected at least " + MODEM_STATUS_HEADER_LENGTH + " bytes"); - } - - return filterStatusBytes(mReadBuffer, dest, totalBytesRead, endpoint.getMaxPacketSize()); + int totalBytesRead = 0; + int bytesAvailable = m_ftDev.getQueueStatus(); + + if (bytesAvailable > 0) { + bytesAvailable = Math.min(4096, bytesAvailable); + try { + totalBytesRead = m_ftDev.read(dest, bytesAvailable, timeoutMillis); + } catch (NullPointerException e) { + final String errorMsg = "Error reading: " + e.getMessage(); + UsbDeviceJNI.qgcLogWarning(errorMsg); + throw new IOException(errorMsg, e); } } + + return totalBytesRead; } @Override public int write(byte[] src, int timeoutMillis) throws IOException { - final UsbEndpoint endpoint = mDevice.getInterface(0).getEndpoint(1); - int offset = 0; - - while (offset < src.length) { - final int writeLength; - final int amtWritten; - - synchronized (mWriteBufferLock) { - final byte[] writeBuffer; - - writeLength = Math.min(src.length - offset, mWriteBuffer.length); - if (offset == 0) { - writeBuffer = src; - } else { - // bulkTransfer does not support offsets, make a copy. - System.arraycopy(src, offset, mWriteBuffer, 0, writeLength); - writeBuffer = mWriteBuffer; - } - - amtWritten = mConnection.bulkTransfer(endpoint, writeBuffer, writeLength, - timeoutMillis); - } - - if (amtWritten <= 0) { - throw new IOException("Error writing " + writeLength - + " bytes at offset " + offset + " length=" + src.length); - } - - //Log.d(TAG, "Wrote amtWritten=" + amtWritten + " attempted=" + writeLength); - offset += amtWritten; + try { + m_ftDev.write(src); + return src.length; + } catch (Exception e) { + UsbDeviceJNI.qgcLogWarning("Error writing: " + e.getMessage()); } - return offset; + return 0; } private int setBaudRate(int baudRate) throws IOException { - long[] vals = convertBaudrate(baudRate); - long actualBaudrate = vals[0]; - long index = vals[1]; - long value = vals[2]; - int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, - SIO_SET_BAUD_RATE_REQUEST, (int) value, (int) index, - null, 0, USB_WRITE_TIMEOUT_MILLIS); - if (result != 0) { - throw new IOException("Setting baudrate failed: result=" + result); + try { + m_ftDev.setBaudRate(baudRate); + return baudRate; + } catch (Exception e) { + UsbDeviceJNI.qgcLogWarning("Error setting baud rate: " + e.getMessage()); } - return (int) actualBaudrate; + return 0; } @Override - public void setParameters(int baudRate, int dataBits, int stopBits, int parity) - throws IOException { + public void setParameters(int baudRate, int dataBits, int stopBits, int parity) throws IOException { setBaudRate(baudRate); - int config = dataBits; - - switch (parity) { - case PARITY_NONE: - config |= (0x00 << 8); - break; - case PARITY_ODD: - config |= (0x01 << 8); - break; - case PARITY_EVEN: - config |= (0x02 << 8); - break; - case PARITY_MARK: - config |= (0x03 << 8); - break; - case PARITY_SPACE: - config |= (0x04 << 8); - break; - default: - throw new IllegalArgumentException("Unknown parity value: " + parity); + switch (dataBits) { + case 7: + dataBits = D2xxManager.FT_DATA_BITS_7; + break; + case 8: + default: + dataBits = D2xxManager.FT_DATA_BITS_8; + break; } switch (stopBits) { - case STOPBITS_1: - config |= (0x00 << 11); - break; - case STOPBITS_1_5: - config |= (0x01 << 11); - break; - case STOPBITS_2: - config |= (0x02 << 11); - break; - default: - throw new IllegalArgumentException("Unknown stopBits value: " + stopBits); - } - - int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, - SIO_SET_DATA_REQUEST, config, 0 /* index */, - null, 0, USB_WRITE_TIMEOUT_MILLIS); - if (result != 0) { - throw new IOException("Setting parameters failed: result=" + result); + default: + case 0: + stopBits = D2xxManager.FT_STOP_BITS_1; + break; + case 1: + stopBits = D2xxManager.FT_STOP_BITS_2; + break; } - } - private long[] convertBaudrate(int baudrate) { - // TODO(mikey): Braindead transcription of libfti method. Clean up, - // using more idiomatic Java where possible. - int divisor = 24000000 / baudrate; - int bestDivisor = 0; - int bestBaud = 0; - int bestBaudDiff = 0; - int fracCode[] = { - 0, 3, 2, 4, 1, 5, 6, 7 - }; - - for (int i = 0; i < 2; i++) { - int tryDivisor = divisor + i; - int baudEstimate; - int baudDiff; - - if (tryDivisor <= 8) { - // Round up to minimum supported divisor - tryDivisor = 8; - } else if (mType != DeviceType.TYPE_AM && tryDivisor < 12) { - // BM doesn't support divisors 9 through 11 inclusive - tryDivisor = 12; - } else if (divisor < 16) { - // AM doesn't support divisors 9 through 15 inclusive - tryDivisor = 16; - } else { - if (mType == DeviceType.TYPE_AM) { - // TODO - } else { - if (tryDivisor > 0x1FFFF) { - // Round down to maximum supported divisor value (for - // BM) - tryDivisor = 0x1FFFF; - } - } - } - - // Get estimated baud rate (to nearest integer) - baudEstimate = (24000000 + (tryDivisor / 2)) / tryDivisor; - - // Get absolute difference from requested baud rate - if (baudEstimate < baudrate) { - baudDiff = baudrate - baudEstimate; - } else { - baudDiff = baudEstimate - baudrate; - } - - if (i == 0 || baudDiff < bestBaudDiff) { - // Closest to requested baud rate so far - bestDivisor = tryDivisor; - bestBaud = baudEstimate; - bestBaudDiff = baudDiff; - if (baudDiff == 0) { - // Spot on! No point trying - break; - } - } - } - - // Encode the best divisor value - long encodedDivisor = (bestDivisor >> 3) | (fracCode[bestDivisor & 7] << 14); - // Deal with special cases for encoded value - if (encodedDivisor == 1) { - encodedDivisor = 0; // 3000000 baud - } else if (encodedDivisor == 0x4001) { - encodedDivisor = 1; // 2000000 baud (BM only) + switch (parity) { + default: + case 0: + parity = D2xxManager.FT_PARITY_NONE; + break; + case 1: + parity = D2xxManager.FT_PARITY_ODD; + break; + case 2: + parity = D2xxManager.FT_PARITY_EVEN; + break; + case 3: + parity = D2xxManager.FT_PARITY_MARK; + break; + case 4: + parity = D2xxManager.FT_PARITY_SPACE; + break; } - // Split into "value" and "index" values - long value = encodedDivisor & 0xFFFF; - long index; - if (mType == DeviceType.TYPE_2232C || mType == DeviceType.TYPE_2232H - || mType == DeviceType.TYPE_4232H) { - index = (encodedDivisor >> 8) & 0xffff; - index &= 0xFF00; - index |= 0 /* TODO mIndex */; - } else { - index = (encodedDivisor >> 16) & 0xffff; + try { + m_ftDev.setDataCharacteristics((byte)dataBits, (byte)stopBits, (byte)parity); + } catch (Exception e) { + UsbDeviceJNI.qgcLogWarning("Error setDataCharacteristics: " + e.getMessage()); } - - // Return the nearest baud rate - return new long[] { - bestBaud, index, value - }; } - @Override public boolean getCD() throws IOException { return false; @@ -515,18 +404,22 @@ public class FtdiSerialDriver extends CommonUsbSerialDriver { @Override public boolean purgeHwBuffers(boolean purgeReadBuffers, boolean purgeWriteBuffers) throws IOException { if (purgeReadBuffers) { - int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, SIO_RESET_REQUEST, - SIO_RESET_PURGE_RX, 0 /* index */, null, 0, USB_WRITE_TIMEOUT_MILLIS); - if (result != 0) { - throw new IOException("Flushing RX failed: result=" + result); + try { + m_ftDev.purge(D2xxManager.FT_PURGE_RX); + } catch (Exception e) { + String errMsg = "Error purgeHwBuffers(RX): "+ e.getMessage(); + UsbDeviceJNI.qgcLogWarning(errMsg); + throw new IOException(errMsg); } } if (purgeWriteBuffers) { - int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, SIO_RESET_REQUEST, - SIO_RESET_PURGE_TX, 0 /* index */, null, 0, USB_WRITE_TIMEOUT_MILLIS); - if (result != 0) { - throw new IOException("Flushing RX failed: result=" + result); + try { + m_ftDev.purge(D2xxManager.FT_PURGE_TX); + } catch (Exception e) { + String errMsg = "Error purgeHwBuffers(TX): " + e.getMessage(); + UsbDeviceJNI.qgcLogWarning(errMsg); + throw new IOException(errMsg); } } diff --git a/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java b/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java index 2e25a761e9c27488479ce383a7ee48bb6227413a..b689ccc7c28e1b47c05c41a016bfe9567ffcdd5a 100644 --- a/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java +++ b/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java @@ -18,6 +18,10 @@ * Project home page: http://code.google.com/p/usb-serial-for-android/ */ +// IMPORTANT NOTE: +// This source has been modified from the original such that testIfSupported only tests for a vendor id +// match. If that matches it allows all product ids through. This provides for better match on unknown boards. + package com.hoho.android.usbserial.driver; import android.hardware.usb.UsbDevice; @@ -230,21 +234,7 @@ public enum UsbSerialProber { * @param supportedDevices map of vendor IDs to product ID(s) * @return {@code true} if supported */ - private static boolean testIfSupported(final UsbDevice usbDevice, - final Map supportedDevices) { - final int[] supportedProducts = supportedDevices.get( - Integer.valueOf(usbDevice.getVendorId())); - if (supportedProducts == null) { - return false; - } - - final int productId = usbDevice.getProductId(); - for (int supportedProductId : supportedProducts) { - if (productId == supportedProductId) { - return true; - } - } - return false; + private static boolean testIfSupported(final UsbDevice usbDevice, final Map supportedDevices) { + return supportedDevices.containsKey(usbDevice.getVendorId()); } - } diff --git a/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java b/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java index 6520ebb6b9258722fa168a19aa9743b9e7820ff8..183d5c25786fa78a4feb9a0fedb255207373c442 100644 --- a/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java +++ b/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java @@ -68,6 +68,8 @@ public class UsbDeviceJNI extends QtActivity implements TextToSpeech.OnInitListe private static TextToSpeech m_tts; private static PowerManager.WakeLock m_wl; + public static Context m_context; + private final static UsbIoManager.Listener m_Listener = new UsbIoManager.Listener() { @@ -90,6 +92,10 @@ public class UsbDeviceJNI extends QtActivity implements TextToSpeech.OnInitListe private static native void nativeDeviceException(int userDataA, String messageA); private static native void nativeDeviceNewData(int userDataA, byte[] dataA); + // Native C++ functions called to log output + public static native void qgcLogDebug(String message); + public static native void qgcLogWarning(String message); + //////////////////////////////////////////////////////////////////////////////////////////////// // // Constructor. Only used once to create the initial instance for the static functions. @@ -252,7 +258,7 @@ public class UsbDeviceJNI extends QtActivity implements TextToSpeech.OnInitListe tempL = tempL + Integer.toString(deviceL.getVendorId()) + ":"; listL[countL] = tempL; countL++; - //Log.i(TAG, "Found " + tempL); + qgcLogDebug("Found " + tempL); } } @@ -273,11 +279,13 @@ public class UsbDeviceJNI extends QtActivity implements TextToSpeech.OnInitListe // calls like close(), read(), and write(). // ///////////////////////////////////////////////////////////////////////////////////////////////// - public static int open(String nameA, int userDataA) + public static int open(Context parentContext, String nameA, int userDataA) { int idL = BAD_PORT; - Log.i(TAG, "Getting device list"); + m_context = parentContext; + + //qgcLogDebug("Getting device list"); if (!getCurrentDevices()) return BAD_PORT; @@ -366,7 +374,7 @@ public class UsbDeviceJNI extends QtActivity implements TextToSpeech.OnInitListe m_ioManager.remove(idL); } - Log.e(TAG, "Port open exception"); + qgcLogWarning("Port open exception: " + exA.getMessage()); return BAD_PORT; } } diff --git a/deploy/create_linux_appimage.sh b/deploy/create_linux_appimage.sh index 5ebb9bd80c9842cb454a3fe225757a9b0aed0bed..57ecb2dd7b3e4b211edc56c6dd31e20d43f24f15 100755 --- a/deploy/create_linux_appimage.sh +++ b/deploy/create_linux_appimage.sh @@ -35,7 +35,8 @@ mkdir -p ${APPDIR} cd ${TMPDIR} wget -c --quiet http://ftp.us.debian.org/debian/pool/main/u/udev/udev_175-7.2_amd64.deb wget -c --quiet http://ftp.us.debian.org/debian/pool/main/e/espeak/espeak_1.46.02-2_amd64.deb -wget -c --quiet http://ftp.us.debian.org/debian/pool/main/libs/libsdl1.2/libsdl1.2debian_1.2.15-5_amd64.deb +wget -c --quiet http://ftp.us.debian.org/debian/pool/main/libs/libsdl2/libsdl2-2.0-0_2.0.2%2bdfsg1-6_amd64.deb + cd ${APPDIR} find ../ -name *.deb -exec dpkg -x {} . \; diff --git a/libs/mavlink/include/mavlink/v1.0 b/libs/mavlink/include/mavlink/v1.0 index e93ac62981a338a7c823364e7c4ff1077e3f8fc1..13a478092fc9c2faa90c553c362e799ba3bad4e8 160000 --- a/libs/mavlink/include/mavlink/v1.0 +++ b/libs/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit e93ac62981a338a7c823364e7c4ff1077e3f8fc1 +Subproject commit 13a478092fc9c2faa90c553c362e799ba3bad4e8 diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 36f37bde1df2dd36661fbcbd6ed5aaf0424c8269..094e765e6353390ac2973023287b7022e696a57e 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 36f37bde1df2dd36661fbcbd6ed5aaf0424c8269 +Subproject commit 094e765e6353390ac2973023287b7022e696a57e diff --git a/libs/qtandroidserialport/src/qserialport_android.cpp b/libs/qtandroidserialport/src/qserialport_android.cpp index 675805a459572798b2cd078cc728e82d17918a57..9e8060c03dae3d8dd006564d78bb0ed3628c2a2f 100644 --- a/libs/qtandroidserialport/src/qserialport_android.cpp +++ b/libs/qtandroidserialport/src/qserialport_android.cpp @@ -46,10 +46,10 @@ #include #include -#include - #include "qserialport_android_p.h" +QGC_LOGGING_CATEGORY(AndroidSerialPortLog, "AndroidSerialPortLog") + QT_BEGIN_NAMESPACE #define BAD_PORT 0 @@ -91,6 +91,30 @@ static void jniDeviceException(JNIEnv *envA, jobject thizA, jint userDataA, jstr } } +static void jniLogDebug(JNIEnv *envA, jobject thizA, jstring messageA) +{ + Q_UNUSED(thizA); + + const char *stringL = envA->GetStringUTFChars(messageA, NULL); + QString logMessage = QString::fromUtf8(stringL); + envA->ReleaseStringUTFChars(messageA, stringL); + if (envA->ExceptionCheck()) + envA->ExceptionClear(); + qCDebug(AndroidSerialPortLog) << logMessage; +} + +static void jniLogWarning(JNIEnv *envA, jobject thizA, jstring messageA) +{ + Q_UNUSED(thizA); + + const char *stringL = envA->GetStringUTFChars(messageA, NULL); + QString logMessage = QString::fromUtf8(stringL); + envA->ReleaseStringUTFChars(messageA, stringL); + if (envA->ExceptionCheck()) + envA->ExceptionClear(); + qWarning() << logMessage; +} + void cleanJavaException() { QAndroidJniEnvironment env; @@ -116,13 +140,15 @@ QSerialPortPrivate::QSerialPortPrivate(QSerialPort *q) void QSerialPortPrivate::setNativeMethods(void) { - __android_log_print(ANDROID_LOG_INFO, kJTag, "Registering Native Functions"); + qCDebug(AndroidSerialPortLog) << "Registering Native Functions"; // REGISTER THE C++ FUNCTION WITH JNI JNINativeMethod javaMethods[] { - {"nativeDeviceHasDisconnected", "(I)V", reinterpret_cast(jniDeviceHasDisconnected)}, - {"nativeDeviceNewData", "(I[B)V", reinterpret_cast(jniDeviceNewData)}, - {"nativeDeviceException", "(ILjava/lang/String;)V", reinterpret_cast(jniDeviceException)} + {"nativeDeviceHasDisconnected", "(I)V", reinterpret_cast(jniDeviceHasDisconnected)}, + {"nativeDeviceNewData", "(I[B)V", reinterpret_cast(jniDeviceNewData)}, + {"nativeDeviceException", "(ILjava/lang/String;)V", reinterpret_cast(jniDeviceException)}, + {"qgcLogDebug", "(Ljava/lang/String;)V", reinterpret_cast(jniLogDebug)}, + {"qgcLogWarning", "(Ljava/lang/String;)V", reinterpret_cast(jniLogWarning)} }; QAndroidJniEnvironment jniEnv; @@ -133,36 +159,36 @@ void QSerialPortPrivate::setNativeMethods(void) jclass objectClass = jniEnv->FindClass(kJniClassName); if(!objectClass) { - __android_log_print(ANDROID_LOG_ERROR, kJTag, "Couldn't find class: %s", kJniClassName); + qWarning() << "Couldn't find class:" << kJniClassName; return; } jint val = jniEnv->RegisterNatives(objectClass, javaMethods, sizeof(javaMethods) / sizeof(javaMethods[0])); - __android_log_print(ANDROID_LOG_INFO, kJTag, "Native Functions Registered"); + if (val < 0) { + qWarning() << "Error registering methods: " << val; + } else { + qCDebug(AndroidSerialPortLog) << "Native Functions Registered"; + } if (jniEnv->ExceptionCheck()) { jniEnv->ExceptionDescribe(); jniEnv->ExceptionClear(); } - - if (val < 0) { - __android_log_print(ANDROID_LOG_ERROR, kJTag, "Error registering methods"); - } } bool QSerialPortPrivate::open(QIODevice::OpenMode mode) { rwMode = mode; - __android_log_print(ANDROID_LOG_INFO, kJTag, "Opening %s", systemLocation.toLatin1().data()); + qCDebug(AndroidSerialPortLog) << "Opening" << systemLocation.toLatin1().data(); - __android_log_print(ANDROID_LOG_INFO, kJTag, "Calling Java Open"); QAndroidJniObject jnameL = QAndroidJniObject::fromString(systemLocation); cleanJavaException(); deviceId = QAndroidJniObject::callStaticMethod( kJniClassName, "open", - "(Ljava/lang/String;I)I", + "(Landroid/content/Context;Ljava/lang/String;I)I", + QtAndroid::androidActivity().object(), jnameL.object(), (jint)this); cleanJavaException(); @@ -171,20 +197,11 @@ bool QSerialPortPrivate::open(QIODevice::OpenMode mode) if (deviceId == BAD_PORT) { - __android_log_print(ANDROID_LOG_ERROR, kJTag, "Error opening %s", systemLocation.toLatin1().data()); + qWarning() << "Error opening %s" << systemLocation.toLatin1().data(); q_ptr->setError(QSerialPort::DeviceNotFoundError); return false; } - __android_log_print(ANDROID_LOG_INFO, kJTag, "Calling Java getDeviceHandle"); - cleanJavaException(); - descriptor = QAndroidJniObject::callStaticMethod( - kJniClassName, - "getDeviceHandle", - "(I)I", - deviceId); - cleanJavaException(); - if (rwMode == QIODevice::WriteOnly) stopReadThread(); @@ -196,7 +213,7 @@ void QSerialPortPrivate::close() if (deviceId == BAD_PORT) return; - __android_log_print(ANDROID_LOG_INFO, kJTag, "Closing %s", systemLocation.toLatin1().data()); + qCDebug(AndroidSerialPortLog) << "Closing" << systemLocation.toLatin1().data(); cleanJavaException(); jboolean resultL = QAndroidJniObject::callStaticMethod( kJniClassName, diff --git a/libs/qtandroidserialport/src/qserialport_android_p.h b/libs/qtandroidserialport/src/qserialport_android_p.h index c10c41cc4a29cd61b0d9b6213a9abca9821fd695..4778774d29689ad99550cd414a87c816eaa81ff6 100644 --- a/libs/qtandroidserialport/src/qserialport_android_p.h +++ b/libs/qtandroidserialport/src/qserialport_android_p.h @@ -49,6 +49,9 @@ #include #include +#include "QGCLoggingCategory.h" + +Q_DECLARE_LOGGING_CATEGORY(AndroidSerialPortLog) QT_BEGIN_NAMESPACE diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.qml b/src/AutoPilotPlugins/PX4/AirframeComponent.qml index 0c049b517100c1c2d4c8e203a31b6b78e5b4e33a..048b045dfac1441cd2672fcfb24d2ca5a1bcd504 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.qml +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.qml @@ -104,8 +104,9 @@ SetupPage { QGCLabel { anchors.fill: parent wrapMode: Text.WordWrap - text: qsTr("Clicking “Apply” will save the changes you have made to your airframe configuration. ") + - qsTr("Your vehicle will also be restarted in order to complete the process.") + text: qsTr("Clicking “Apply” will save the changes you have made to your airframe configuration.

\ +All vehicle parameters other than Radio Calibration will be reset.

\ +Your vehicle will also be restarted in order to complete the process.") } } } diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 67f947e6750d252492bcd973cc9aebe47a6c978f..ce0cb02a96a7cad38b691c2fd40e4e978cb75981 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -14,10 +14,10 @@ - + Simon Wilks <simon@px4.io> Flying Wing - https://pixhawk.org/platforms/planes/bormatec_camflyer_q + http://www.sparkletech.hk/ feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel @@ -47,10 +47,14 @@ right aileron throttle - - Lorenz Meier <lorenz@px4.io> + + Simon Wilks <simon@px4.io> Flying Wing - https://pixhawk.org/platforms/planes/z-84_wing_wing + + + Simon Wilks <simon@px4.io> + Flying Wing + https://pixhawk.org/platforms/planes/bormatec_camflyer_q feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel @@ -58,18 +62,14 @@ right aileron throttle - - Simon Wilks <simon@px4.io> - Flying Wing - Simon Wilks <simon@px4.io> Flying Wing - - Simon Wilks <simon@px4.io> + + Lorenz Meier <lorenz@px4.io> Flying Wing - http://www.sparkletech.hk/ + https://pixhawk.org/platforms/planes/z-84_wing_wing feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel @@ -82,6 +82,12 @@ Flying Wing + + + Bart Slinger <bartslinger@gmail.com> + Helicopter + + Anton Babushkin <anton@px4.io> @@ -177,16 +183,12 @@ Anton Babushkin <anton@px4.io> Quadrotor Wide - - Thomas Gubler <thomas@px4.io> - Quadrotor Wide - Simon Wilks <simon@px4.io> Quadrotor Wide - - Anton Matosov <anton.matosov@gmail.com> + + Thomas Gubler <thomas@px4.io> Quadrotor Wide @@ -195,75 +197,90 @@ Lorenz Meier <lorenz@px4.io> Quadrotor x - + Lorenz Meier <lorenz@px4.io> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - James Goppert <james.goppert@gmail.com> + + Pavel Kirienko <pavel@px4.io> + Quadrotor x + + + Leon Mueller <thedevleon> + Quadrotor x + + + Lorenz Meier <lorenz@px4.io> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Lorenz Meier <lorenz@px4.io> + + Blankered Quadrotor x - - Mark Whitehorn <kd0aij@gmail.com> + + Lorenz Meier <lorenz@px4.io> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Lorenz Meier <lorenz@px4.io> + + Mark Whitehorn <kd0aij@gmail.com> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Lorenz Meier <lorenz@px4.io> + + James Goppert <james.goppert@gmail.com> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Pavel Kirienko <pavel@px4.io> + + Lorenz Meier <lorenz@px4.io> Quadrotor x Thomas Gubler <thomas@px4.io> Quadrotor x - - Andreas Antener <andreas@uaventure.com> - Quadrotor x - - - Blankered - Quadrotor x - - + Mark Whitehorn <kd0aij@gmail.com> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - + James Goppert <james.goppert@gmail.com> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel + + Quadrotor x + + + Michael Schaeuble + Quadrotor x + + + Leon Mueller <thedevleon> + Quadrotor x + + + Andreas Antener <andreas@uaventure.com> + Quadrotor x + @@ -271,6 +288,10 @@ + + Anton Babushkin <anton@px4.io> + Simulation + Lorenz Meier <lorenz@px4.io> Simulation @@ -279,28 +300,12 @@ rudder throttle - - Anton Babushkin <anton@px4.io> - Simulation - Anton Babushkin <anton@px4.io> Simulation - - Thomas Gubler <thomas@px4.io> - Simulation - - - Thomas Gubler <thomas@px4.io> - Simulation - - - Lorenz Meier <lorenz@px4.io> - Standard Plane - Lorenz Meier <lorenz@px4.io> Standard Plane @@ -313,7 +318,25 @@ throttle flaps - + + Andreas Antener <andreas@uaventure.com> + Standard Plane + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + aileron + aileron + elevator + rudder + throttle + wheel + flaps + + + Lorenz Meier <lorenz@px4.io> + Standard Plane + + Lorenz Meier <lorenz@px4.io> Standard Plane feed-through of RC AUX1 channel @@ -335,7 +358,7 @@ elevator throttle - + Lorenz Meier <lorenz@px4.io> Standard Plane feed-through of RC AUX1 channel @@ -347,30 +370,8 @@ rudder flaps - - Andreas Antener <andreas@uaventure.com> - Standard Plane - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - aileron - aileron - elevator - rudder - throttle - wheel - flaps - - - Simon Wilks <simon@uaventure.com> - Standard VTOL - - - Simon Wilks <simon@uaventure.com> - Standard VTOL - Sander Smeets <sander@droneslab.com> Standard VTOL @@ -379,6 +380,14 @@ Sander Smeets <sander@droneslab.com> Standard VTOL + + Simon Wilks <simon@uaventure.com> + Standard VTOL + + + Simon Wilks <simon@uaventure.com> + Standard VTOL + Andreas Antener <andreas@uaventure.com> Standard VTOL @@ -407,24 +416,24 @@ - + Roman Bapst <roman@px4.io> VTOL Quad Tailsitter - + Roman Bapst <roman@px4.io> VTOL Quad Tailsitter - - Roman Bapst <roman@px4.io> - VTOL Tiltrotor - Samay Siga <samay_s@icloud.com> VTOL Tiltrotor + + Roman Bapst <roman@px4.io> + VTOL Tiltrotor + diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index b68ea44a408b51db987c93666aaf9dc1d2fac8e8..83682333a97799cff36ca7d8c7d6dce926e8624b 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -446,9 +446,9 @@ velocity Distance, mission controlled - + Camera trigger pin - Selects which pin is used, ranges from 1 to 6 (AUX1-AUX6 on px4fmu-v2 and the rail pins on px4fmu-v4). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 34 would trigger on pins 3 and 4. + Selects which pin is used, ranges from 1 to 6 (AUX1-AUX6 on px4fmu-v2 and the rail pins on px4fmu-v4). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6. 1 123456 0 @@ -647,7 +647,7 @@ velocity Time-out for auto disarm after landing - A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A value of zero means that automatic disarming is disabled. + A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. The vehicle will also auto-disarm right after arming if it has not even flown, however the time will be longer by a factor of 5. A value of zero means that automatic disarming is disabled. 0 20 s @@ -689,6 +689,31 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action + + Airfield home Lat + Latitude of airfield home waypoint + -900000000 + 900000000 + deg * 1e7 + modules/navigator + + + Airfield home Lon + Longitude of airfield home waypoint + -1800000000 + 1800000000 + deg * 1e7 + modules/navigator + + + Airfield home alt + Altitude of airfield home waypoint + -50 + m + 1 + 0.5 + modules/navigator + Comms hold wait time The amount of time in seconds the system should wait at the comms hold waypoint @@ -748,31 +773,6 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action modules/navigator - - Airfield home Lat - Latitude of airfield home waypoint - -900000000 - 900000000 - deg * 1e7 - modules/navigator - - - Airfield home Lon - Longitude of airfield home waypoint - -1800000000 - 1800000000 - deg * 1e7 - modules/navigator - - - Airfield home alt - Altitude of airfield home waypoint - -50 - m - 1 - 0.5 - modules/navigator - @@ -1313,7 +1313,7 @@ value will determine the minimum airspeed which will still be fused 1 modules/ekf2 - + Time constant of the velocity output prediction and smoothing filter 1.0 s @@ -1900,6 +1900,16 @@ value will determine the minimum airspeed which will still be fused + + Cruise Airspeed + The fixed wing controller tries to fly at this airspeed. + 0.0 + 40 + m/s + 1 + 0.5 + modules/navigator + Minimum Airspeed If the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. @@ -2069,16 +2079,6 @@ value will determine the minimum airspeed which will still be fused 0.01 modules/fw_pos_control_l1 - - Cruise Airspeed - The fixed wing controller tries to fly at this airspeed. - 0.0 - 40 - m/s - 1 - 0.5 - modules/navigator - @@ -2213,45 +2213,25 @@ but also ignore less noise 1 modules/navigator - + Max horizontal distance in meters - Set to > 0 to activate a geofence action if horizontal distance to home exceeds this value. - -1 - 5000 + Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + 0 + 10000 m 1 modules/navigator - + Max vertical distance in meters - Set to > 0 to activate a geofence action if vertical distance to home exceeds this value. - -1 + Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + 0 + 10000 m 1 modules/navigator - - - Consider mount operation mode - If set to 1, mount mode will be enforced. - - drivers/gimbal - - - Auxiliary switch to set mount operation mode - Set to 0 to disable manual mode control. If set to an auxiliary switch: Switch off means the gimbal is put into safe/locked position. Switch on means the gimbal can move freely, and landing gear will be retracted if applicable. - 0 - 3 - drivers/gimbal - - AUX1 - Disable - AUX3 - AUX2 - - - Multicopter max climb rate @@ -2376,6 +2356,11 @@ but also ignore less noise + + Publish AGL as Z + + modules/local_position_estimator + Optical flow z offset from center -1 @@ -2384,15 +2369,23 @@ but also ignore less noise 3 modules/local_position_estimator - - Optical flow xy standard deviation - 0.01 + + Optical flow scale + 0.1 + 10.0 + m + 3 + modules/local_position_estimator + + + Optical flow gyro compensation + -1 1 m 3 modules/local_position_estimator - + Optical flow minimum quality threshold 0 255 @@ -2431,7 +2424,7 @@ but also ignore less noise 3 modules/local_position_estimator - + Accelerometer xy noise density Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. 0.00001 @@ -2440,7 +2433,7 @@ but also ignore less noise 4 modules/local_position_estimator - + Accelerometer z noise density Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) 0.00001 @@ -2519,7 +2512,15 @@ EPV used if greater than this value 3 modules/local_position_estimator - + + Vision delay compensaton + 0 + 0.1 + sec + 2 + modules/local_position_estimator + + Vision xy standard deviation 0.01 1 @@ -2540,12 +2541,12 @@ EPV used if greater than this value modules/local_position_estimator - + Vicon position standard deviation - 0.01 + 0.0001 1 m - 3 + 4 modules/local_position_estimator @@ -2574,15 +2575,24 @@ EPV used if greater than this value 8 modules/local_position_estimator + + Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) + 0 + 1 + (m/s)/(sqrt(hz)) + 3 + modules/local_position_estimator + - Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) + Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) +Used to calculate increased terrain random walk nosie due to movement 0 100 % 3 modules/local_position_estimator - + Flow gyro high pass filter cut off frequency 0 2 @@ -2614,12 +2624,12 @@ EPV used if greater than this value 0 modules/local_position_estimator - - Required xy standard deviation to publish position - 0.3 - 5.0 - m - 1 + + Required velocity xy standard deviation to publish position + 0.01 + 1.0 + m/s + 3 modules/local_position_estimator @@ -2630,6 +2640,14 @@ EPV used if greater than this value 1 modules/local_position_estimator + + Land detector z standard deviation + 0.001 + 10.0 + m + 3 + modules/local_position_estimator + @@ -2644,7 +2662,7 @@ EPV used if greater than this value 250 modules/mavlink - + MAVLink protocol version modules/mavlink @@ -2742,28 +2760,6 @@ EPV used if greater than this value - - Set offboard loss failsafe mode - The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. - modules/commander - - Loiter - Land at current position - Return to Land - - - - Set offboard loss failsafe mode when RC is available - The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. - modules/commander - - Altitude control - Position control - Return to Land - Manual - Land at current position - - Take-off altitude This is the minimum altitude the system will take off to. @@ -2915,137 +2911,132 @@ EPV used if greater than this value Return to Land - - - - Roll P gain - Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - 0.0 - examples/mc_att_control_multiplatform - - - Roll rate P gain - Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - examples/mc_att_control_multiplatform + + Set offboard loss failsafe mode + The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + modules/commander + + Loiter + Land at current position + Return to Land + - - Roll rate I gain - Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - examples/mc_att_control_multiplatform + + Set offboard loss failsafe mode when RC is available + The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + modules/commander + + Altitude control + Position control + Return to Land + Manual + Land at current position + - - Roll rate D gain - Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - examples/mc_att_control_multiplatform + + + + Mount input mode +RC uses the AUX input channels (see MNT_MAN_* parameters), +MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the +MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount + 0 + 3 + drivers/vmount + + RC + DISABLE + MAVLINK_DO_MOUNT + MAVLINK_ROI + - - Pitch P gain - Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - 0.0 - 1/s - examples/mc_att_control_multiplatform + + Mount output mode +AUX uses the mixer output Control Group #2. +MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages +to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) + 0 + 1 + drivers/vmount + + MAVLINK + AUX + - - Pitch rate P gain - Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - examples/mc_att_control_multiplatform + + Mavlink System ID (if MNT_MODE_OUT is MAVLINK) + drivers/vmount - - Pitch rate I gain - Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - examples/mc_att_control_multiplatform + + Mavlink Component ID (if MNT_MODE_OUT is MAVLINK) + drivers/vmount - - Pitch rate D gain - Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - examples/mc_att_control_multiplatform + + Mixer value for selecting normal mode +if required by the gimbal (only in AUX output mode) + -1.0 + 1.0 + 3 + drivers/vmount - - Yaw P gain - Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - 0.0 - 1/s - examples/mc_att_control_multiplatform + + Mixer value for selecting a locking mode +if required for the gimbal (only in AUX output mode) + -1.0 + 1.0 + 3 + drivers/vmount - - Yaw rate P gain - Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - examples/mc_att_control_multiplatform + + This enables the mount to be manually controlled when no ROI is set + If set to 1, the mount will be controlled by the AUX channels below when no ROI is set. + + drivers/vmount - - Yaw rate I gain - Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - examples/mc_att_control_multiplatform + + Auxiliary channel to control roll (in AUX input or manual mode) + 0 + 5 + drivers/vmount + + AUX1 + Disable + AUX3 + AUX2 + AUX5 + AUX4 + - - Yaw rate D gain - Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - examples/mc_att_control_multiplatform - - - Yaw feed forward - Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot. - 0.0 - 1.0 - examples/mc_att_control_multiplatform - - - Max yaw rate - Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. - 0.0 - 360.0 - deg/s - examples/mc_att_control_multiplatform - - - Max acro roll rate - 0.0 - 360.0 - deg/s - examples/mc_att_control_multiplatform - - - Max acro pitch rate - 0.0 - 360.0 - deg/s - examples/mc_att_control_multiplatform - - - Max acro yaw rate - 0.0 - deg/s - examples/mc_att_control_multiplatform - - - Max manual roll - 0.0 - 90.0 - deg - examples/mc_pos_control_multiplatform - - - Max manual pitch - 0.0 - 90.0 - deg - examples/mc_pos_control_multiplatform + + Auxiliary channel to control pitch (in AUX input or manual mode) + 0 + 5 + drivers/vmount + + AUX1 + Disable + AUX3 + AUX2 + AUX5 + AUX4 + - - Max manual yaw rate - 0.0 - deg/s - examples/mc_pos_control_multiplatform + + Auxiliary channel to control yaw (in AUX input or manual mode) + 0 + 5 + drivers/vmount + + AUX1 + Disable + AUX3 + AUX2 + AUX5 + AUX4 + + + Roll time constant Reduce if the system is too twitchy, increase if the response is too slow and sluggish. @@ -3278,114 +3269,155 @@ EPV used if greater than this value 0.01 modules/mc_att_control - - - - Minimum thrust - Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. + + Threshold for Throttle PID Attenuation (TPA) + Magnitude of throttle setpoint at which to begin attenuating roll/pitch P gain 0.0 1.0 - examples/mc_pos_control_multiplatform + 2 + 0.1 + modules/mc_att_control - - Maximum thrust - Limit max allowed thrust. + + Slope for Throttle PID Attenuation (TPA) + Rate at which to attenuate roll/pitch P gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - slope*(abs(throttle)-breakpoint)) 0.0 - 1.0 - examples/mc_pos_control_multiplatform + 2.0 + 2 + 0.1 + modules/mc_att_control - - Proportional gain for vertical position error + + Max manual roll 0.0 + 90.0 + deg examples/mc_pos_control_multiplatform - - Proportional gain for vertical velocity error + + Max manual pitch 0.0 + 90.0 + deg examples/mc_pos_control_multiplatform - - Integral gain for vertical velocity error - Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. + + Max manual yaw rate 0.0 + deg/s examples/mc_pos_control_multiplatform - - Differential gain for vertical velocity error + + Roll P gain + Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 0.0 - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Maximum vertical velocity - Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL). + + Roll rate P gain + Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.0 - m/s - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Vertical velocity feed forward - Feed forward weight for altitude control in stabilized modes (ALTCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + + Roll rate I gain + Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 - 1.0 - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Proportional gain for horizontal position error + + Roll rate D gain + Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Proportional gain for horizontal velocity error + + Pitch P gain + Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 0.0 - examples/mc_pos_control_multiplatform + 1/s + examples/mc_att_control_multiplatform - - Integral gain for horizontal velocity error - Non-zero value allows to resist wind. + + Pitch rate P gain + Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.0 - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again + + Pitch rate I gain + Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Maximum horizontal velocity - Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL). + + Pitch rate D gain + Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 - m/s - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Horizontal velocity feed forward - Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + + Yaw P gain + Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + 0.0 + 1/s + examples/mc_att_control_multiplatform + + + Yaw rate P gain + Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.0 + examples/mc_att_control_multiplatform + + + Yaw rate I gain + Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 + examples/mc_att_control_multiplatform + + + Yaw rate D gain + Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + examples/mc_att_control_multiplatform + + + Yaw feed forward + Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot. 0.0 1.0 - examples/mc_pos_control_multiplatform + examples/mc_att_control_multiplatform - - Maximum tilt angle in air - Limits maximum tilt in AUTO and POSCTRL modes during flight. + + Max yaw rate + Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. 0.0 - 90.0 - deg - examples/mc_pos_control_multiplatform + 360.0 + deg/s + examples/mc_att_control_multiplatform - - Maximum tilt during landing - Limits maximum tilt angle on landing. + + Max acro roll rate 0.0 - 90.0 - deg - examples/mc_pos_control_multiplatform + 360.0 + deg/s + examples/mc_att_control_multiplatform - - Landing descend rate + + Max acro pitch rate 0.0 - m/s - examples/mc_pos_control_multiplatform + 360.0 + deg/s + examples/mc_att_control_multiplatform + + + Max acro yaw rate + 0.0 + deg/s + examples/mc_att_control_multiplatform + + Minimum thrust in auto thrust control It's recommended to set it > 0 to avoid free fall with zero thrust. @@ -3647,40 +3679,207 @@ EPV used if greater than this value Maximum vertical velocity for which position hold is enabled (use 0 to disable check) 0.0 - 3.0 + 3.0 + m/s + 2 + modules/mc_pos_control + + + Low pass filter cut freq. for numerical velocity derivative + 0.0 + 10 + Hz + 2 + modules/mc_pos_control + + + Maximum horizonal acceleration in velocity controlled modes + 2.0 + 15.0 + m/s/s + 2 + 1 + modules/mc_pos_control + + + Altitude control mode, note mode 1 only tested with LPE + 0 + 1 + modules/mc_pos_control + + Terrain following + Altitude following + + + + Minimum thrust + Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. + 0.0 + 1.0 + examples/mc_pos_control_multiplatform + + + Maximum thrust + Limit max allowed thrust. + 0.0 + 1.0 + examples/mc_pos_control_multiplatform + + + Proportional gain for vertical position error + 0.0 + examples/mc_pos_control_multiplatform + + + Proportional gain for vertical velocity error + 0.0 + examples/mc_pos_control_multiplatform + + + Integral gain for vertical velocity error + Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. + 0.0 + examples/mc_pos_control_multiplatform + + + Differential gain for vertical velocity error + 0.0 + examples/mc_pos_control_multiplatform + + + Maximum vertical velocity + Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL). + 0.0 + m/s + examples/mc_pos_control_multiplatform + + + Vertical velocity feed forward + Feed forward weight for altitude control in stabilized modes (ALTCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + 0.0 + 1.0 + examples/mc_pos_control_multiplatform + + + Proportional gain for horizontal position error + 0.0 + examples/mc_pos_control_multiplatform + + + Proportional gain for horizontal velocity error + 0.0 + examples/mc_pos_control_multiplatform + + + Integral gain for horizontal velocity error + Non-zero value allows to resist wind. + 0.0 + examples/mc_pos_control_multiplatform + + + Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again + 0.0 + examples/mc_pos_control_multiplatform + + + Maximum horizontal velocity + Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL). + 0.0 + m/s + examples/mc_pos_control_multiplatform + + + Horizontal velocity feed forward + Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + 0.0 + 1.0 + examples/mc_pos_control_multiplatform + + + Maximum tilt angle in air + Limits maximum tilt in AUTO and POSCTRL modes during flight. + 0.0 + 90.0 + deg + examples/mc_pos_control_multiplatform + + + Maximum tilt during landing + Limits maximum tilt angle on landing. + 0.0 + 90.0 + deg + examples/mc_pos_control_multiplatform + + + Landing descend rate + 0.0 m/s - 2 - modules/mc_pos_control + examples/mc_pos_control_multiplatform - - Low pass filter cut freq. for numerical velocity derivative - 0.0 - 10 - Hz - 2 - modules/mc_pos_control + + + + Set the minimum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for industry default or 900 to increase servo travel. + 800 + 1400 + us + true + modules/sensors - - Maximum horizonal acceleration in velocity controlled modes - 2.0 - 15.0 - m/s/s - 2 - 1 - modules/mc_pos_control + + Set the maximum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for industry default or 2100 to increase servo travel. + 1600 + 2200 + us + true + modules/sensors - - Altitude control mode, note mode 1 only tested with LPE + + Set the disarmed PWM for MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. 0 - 1 - modules/mc_pos_control - - Terrain following - Altitude following - + 2200 + us + true + modules/sensors + + + Set the minimum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for default or 900 to increase servo travel + 800 + 1400 + us + true + modules/sensors + + + Set the maximum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for default or 2100 to increase servo travel + 1600 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for AUX outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + 0 + 2200 + us + true + modules/sensors + + + Minimum motor rise time (slew rate limit) + Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled. + 0.0 + s/(1000*PWM) + modules/sensors - - Invert direction of aux output channel 1 Set to 1 to invert the channel, 0 for default direction. @@ -3785,60 +3984,6 @@ EPV used if greater than this value drivers/px4io - - Set the minimum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for industry default or 900 to increase servo travel. - 800 - 1400 - us - true - modules/sensors - - - Set the maximum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for industry default or 2100 to increase servo travel. - 1600 - 2200 - us - true - modules/sensors - - - Set the disarmed PWM for MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. - 0 - 2200 - us - true - modules/sensors - - - Set the minimum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for default or 900 to increase servo travel - 800 - 1400 - us - true - modules/sensors - - - Set the maximum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for default or 2100 to increase servo travel - 1600 - 2200 - us - true - modules/sensors - - - Set the disarmed PWM for AUX outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. - 0 - 2200 - us - true - modules/sensors - @@ -4256,33 +4401,6 @@ EPV used if greater than this value - - Roll trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 - 2 - 0.01 - modules/commander - - - Pitch trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 - 2 - 0.01 - modules/commander - - - Yaw trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 - 2 - 0.01 - modules/commander - RC Channel 1 Minimum Minimum value for RC channel 1 @@ -5389,6 +5507,33 @@ EPV used if greater than this value 2000 modules/sensors + + Roll trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + modules/commander + + + Pitch trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + modules/commander + + + Yaw trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + modules/commander + @@ -5701,6 +5846,33 @@ EPV used if greater than this value Channel 8 + + Landing gear switch channel + 0 + 18 + modules/sensors + + Channel 11 + Channel 10 + Channel 13 + Channel 12 + Channel 15 + Channel 14 + Channel 17 + Channel 16 + Channel 18 + Channel 1 + Unassigned + Channel 3 + Channel 2 + Channel 5 + Channel 4 + Channel 7 + Channel 6 + Channel 9 + Channel 8 + + Threshold for selecting assist mode 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th @@ -5771,6 +5943,13 @@ EPV used if greater than this value 1 modules/sensors + + Threshold for the landing gear switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + modules/sensors + @@ -5900,14 +6079,6 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL - - UTC offset (unit: min) - the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets - -1000 - 1000 - min - modules/logger - Logging rate A value of -1 indicates the commandline argument should be obeyed. A value of 0 sets the minimum rate, any other value is interpreted as rate in Hertz. This parameter is only read out before logging starts (which commonly is before arming). @@ -5948,6 +6119,14 @@ This is used for gathering replay logs for the ekf2 module Medium priority + + UTC offset (unit: min) + the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets + -1000 + 1000 + min + modules/logger + @@ -6543,6 +6722,12 @@ This is used for gathering replay logs for the ekf2 module true modules/sensors + + TeraRanger One (trone) + + true + modules/sensors + Lightware SF1xx laser rangefinder 0 @@ -6597,19 +6782,34 @@ This is used for gathering replay logs for the ekf2 module ms examples/subscriber - - Float Demonstration Parameter in the Example - examples/subscriber + + Float Demonstration Parameter in the Example + examples/subscriber + + + + + Operating channel of the NRF51 + 0 + 125 + modules/syslink + + + Operating datarate of the NRF51 + 0 + 2 + modules/syslink + + + Operating address of the NRF51 (most significant byte) + modules/syslink + + + Operating address of the NRF51 (least significant 4 bytes) + modules/syslink - - RGB Led brightness limit - Set to 0 to disable, 1 for minimum brightness up to 15 (max) - 0 - 15 - drivers/rgbled - Auto-start script index CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system. @@ -6671,13 +6871,16 @@ This is used for gathering replay logs for the ekf2 module modules/systemlib FrSky Telemetry + Crazyflie (Syslink) Normal Telemetry (57600 baud, 8N1) Command Receiver (57600 baud, 8N1) OSD (57600 baud, 8N1) + Normal Telemetry (38400 baud, 8N1) Disabled ESP8266 (921600 baud, 8N1) Companion Link (57600 baud, 8N1) Companion Link (921600 baud, 8N1) + Normal Telemetry (19200 baud, 8N1) @@ -6697,6 +6900,13 @@ This is used for gathering replay logs for the ekf2 module sdlog2 (default) + + RGB Led brightness limit + Set to 0 to disable, 1 for minimum brightness up to 15 (max) + 0 + 15 + drivers/rgbled + @@ -6780,73 +6990,14 @@ This is used for gathering replay logs for the ekf2 module bit/s modules/uavcan - - - - Target throttle value for pusher/puller motor during the transition to fw mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Maximum allowed down-pitch the controller is able to demand. This prevents large, negative -lift values being created when facing strong winds. The vehicle will use the pusher motor -to accelerate forward if necessary - 0.0 - 45.0 - modules/vtol_att_control - - - Fixed wing thrust scale for hover forward flight - Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. - 0.0 - 2.0 - modules/vtol_att_control - - - Position of tilt servo in mc mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Position of tilt servo in transition mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Position of tilt servo in fw mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Duration of front transition phase 2 - Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. - 0.1 - 5.0 - s - 3 - 0.01 - modules/vtol_att_control - - - The channel number of motors that must be turned off in fixed wing mode + + UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints 0 - 12345678 - 0 - 1 - modules/vtol_att_control + 1 + modules/uavcan + + VTOL number of engines 0 @@ -7040,6 +7191,71 @@ to accelerate forward if necessary 200.0 modules/vtol_att_control + + Position of tilt servo in mc mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Position of tilt servo in transition mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Position of tilt servo in fw mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Duration of front transition phase 2 + Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. + 0.1 + 5.0 + s + 3 + 0.01 + modules/vtol_att_control + + + The channel number of motors that must be turned off in fixed wing mode + 0 + 12345678 + 0 + 1 + modules/vtol_att_control + + + Target throttle value for pusher/puller motor during the transition to fw mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Maximum allowed down-pitch the controller is able to demand. This prevents large, negative +lift values being created when facing strong winds. The vehicle will use the pusher motor +to accelerate forward if necessary + 0.0 + 45.0 + modules/vtol_att_control + + + Fixed wing thrust scale for hover forward flight + Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. + 0.0 + 2.0 + modules/vtol_att_control + @@ -7297,21 +7513,49 @@ Maps the change of airspeed error to the acceleration setpoint - - EXFW_HDNG_P - examples/fixedwing_control + + SEG_TH2V_P + modules/segway - - EXFW_ROLL_P - examples/fixedwing_control + + SEG_TH2V_I + modules/segway - - EXFW_PITCH_P - examples/fixedwing_control + + SEG_TH2V_I_MAX + modules/segway - - RV_YAW_P - examples/rover_steering_control + + SEG_Q2V + modules/segway + + + Failsafe channel mapping + The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific rc channel to use + 0 + 18 + modules/sensors + + Channel 11 + Channel 10 + Channel 13 + Channel 12 + Channel 15 + Channel 14 + Channel 17 + Channel 16 + Channel 18 + Channel 1 + Unassigned + Channel 3 + Channel 2 + Channel 5 + Channel 4 + Channel 7 + Channel 6 + Channel 9 + Channel 8 + First flightmode slot (1000-1160) @@ -7439,49 +7683,21 @@ Maps the change of airspeed error to the acceleration setpoint Stabilized - - SEG_TH2V_P - modules/segway - - - SEG_TH2V_I - modules/segway + + EXFW_HDNG_P + examples/fixedwing_control - - SEG_TH2V_I_MAX - modules/segway + + EXFW_ROLL_P + examples/fixedwing_control - - SEG_Q2V - modules/segway + + EXFW_PITCH_P + examples/fixedwing_control - - Failsafe channel mapping - The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific rc channel to use - 0 - 18 - modules/sensors - - Channel 11 - Channel 10 - Channel 13 - Channel 12 - Channel 15 - Channel 14 - Channel 17 - Channel 16 - Channel 18 - Channel 1 - Unassigned - Channel 3 - Channel 2 - Channel 5 - Channel 4 - Channel 7 - Channel 6 - Channel 9 - Channel 8 - + + RV_YAW_P + examples/rover_steering_control diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 24a8458a801644624c771501034e466d60ea39bf..2d3b7f2df94df111cea747b4e3a7cdc9701fd063 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -197,7 +197,8 @@ Map { property alias drawingPolygon: polygonDrawer.hoverEnabled property bool adjustingPolygon: false - property bool polygonReady: polygonDrawerPolygon.path.length > 3 ///< true: enough points have been captured to create a closed polygon + property bool polygonReady: polygonDrawerPolygonSet.path.length > 2 ///< true: enough points have been captured to create a closed polygon + property bool justClicked: false property var _callbackObject @@ -220,8 +221,7 @@ Map { return false } - var polygonPath = polygonDrawerPolygon.path - polygonPath.pop() // get rid of drag coordinate + var polygonPath = polygonDrawerPolygonSet.path _cancelCapturePolygon() polygonDrawer._callbackObject.polygonCaptureFinished(polygonPath) return true @@ -322,10 +322,13 @@ Map { polygonDrawerNextPoint.path = [ bogusCoord, bogusCoord ] polygonDrawerPolygon.path = [ ] polygonDrawerNextPoint.path = [ ] + polygonDrawerPolygonSet.path = [ bogusCoord, bogusCoord ] + polygonDrawerPolygonSet.path = [ ] } onClicked: { if (mouse.button == Qt.LeftButton) { + polygonDrawer.justClicked = true if (polygonDrawerPolygon.path.length > 2) { // Make sure the new line doesn't intersect the existing polygon var lastSegment = polygonDrawerPolygon.path.length - 2 @@ -349,8 +352,7 @@ Map { // Update finalized coordinate polygonPath[polygonDrawerPolygon.path.length - 1] = clickCoordinate } - // Add next drag coordinate - polygonPath.push(clickCoordinate) + polygonDrawerPolygonSet.path = polygonPath polygonDrawerPolygon.path = polygonPath } else if (polygonDrawer.polygonReady) { finishCapturePolygon() @@ -360,14 +362,18 @@ Map { onPositionChanged: { if (polygonDrawerPolygon.path.length) { var dragCoordinate = _map.toCoordinate(Qt.point(mouse.x, mouse.y)) + var polygonPath = polygonDrawerPolygon.path + if (polygonDrawer.justClicked){ + polygonPath.push(dragCoordinate) + polygonDrawer.justClicked = false + } // Update drag line polygonDrawerNextPoint.path = [ polygonDrawerPolygon.path[polygonDrawerPolygon.path.length - 2], dragCoordinate ] - // Update drag coordinate - var polygonPath = polygonDrawerPolygon.path polygonPath[polygonDrawerPolygon.path.length - 1] = dragCoordinate polygonDrawerPolygon.path = polygonPath + } } } @@ -377,14 +383,20 @@ Map { id: polygonDrawerPolygon color: "blue" opacity: 0.5 - visible: polygonDrawer.drawingPolygon + visible: polygonDrawerPolygon.path.length > 2 + } + MapPolygon { + id: polygonDrawerPolygonSet + color: 'green' + opacity: 0.5 + visible: polygonDrawer.polygonReady } /// Next line for polygon MapPolyline { id: polygonDrawerNextPoint line.color: "green" - line.width: 5 + line.width: 3 visible: polygonDrawer.drawingPolygon } diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 4c5fc64d90a77c3cc61a9293075849adb2657b3d..17ce67b478e49a66e087359aeef9597b0df59c3f 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -23,6 +23,8 @@ const char* Joystick::_calibratedSettingsKey = "Calibrated1"; // Increment const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1"; const char* Joystick::_throttleModeSettingsKey = "ThrottleMode"; const char* Joystick::_exponentialSettingsKey = "Exponential"; +const char* Joystick::_accumulatorSettingsKey = "Accumulator"; +const char* Joystick::_deadbandSettingsKey = "Deadband"; const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { "RollAxis", @@ -46,6 +48,8 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC , _lastButtonBits(0) , _throttleMode(ThrottleModeCenterZero) , _exponential(false) + , _accumulator(false) + , _deadband(false) , _activeVehicle(NULL) , _pollingStartedForCalibration(false) , _multiVehicleManager(multiVehicleManager) @@ -86,16 +90,19 @@ void Joystick::_loadSettings(void) _calibrated = settings.value(_calibratedSettingsKey, false).toBool(); _exponential = settings.value(_exponentialSettingsKey, false).toBool(); + _accumulator = settings.value(_accumulatorSettingsKey, false).toBool(); + _deadband = settings.value(_deadbandSettingsKey, false).toBool(); _throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk); badSettings |= !convertOk; - qCDebug(JoystickLog) << "_loadSettings calibrated:throttlemode:exponential:badsettings" << _calibrated << _throttleMode << _exponential << badSettings; + qCDebug(JoystickLog) << "_loadSettings calibrated:throttlemode:exponential:deadband:badsettings" << _calibrated << _throttleMode << _exponential << _deadband << badSettings; QString minTpl ("Axis%1Min"); QString maxTpl ("Axis%1Max"); QString trimTpl ("Axis%1Trim"); QString revTpl ("Axis%1Rev"); + QString deadbndTpl ("Axis%1Deadbnd"); for (int axis=0; axis<_axisCount; axis++) { Calibration_t* calibration = &_rgCalibration[axis]; @@ -109,9 +116,13 @@ void Joystick::_loadSettings(void) calibration->max = settings.value(maxTpl.arg(axis), 32767).toInt(&convertOk); badSettings |= !convertOk; + calibration->deadband = settings.value(deadbndTpl.arg(axis), 0).toInt(&convertOk); + badSettings |= !convertOk; + calibration->reversed = settings.value(revTpl.arg(axis), false).toBool(); - qCDebug(JoystickLog) << "_loadSettings axis:min:max:trim:reversed:badsettings" << axis << calibration->min << calibration->max << calibration->center << calibration->reversed << badSettings; + + qCDebug(JoystickLog) << "_loadSettings axis:min:max:trim:reversed:deadband:badsettings" << axis << calibration->min << calibration->max << calibration->center << calibration->reversed << calibration->deadband << badSettings; } for (int function=0; functionmin); settings.setValue(maxTpl.arg(axis), calibration->max); settings.setValue(revTpl.arg(axis), calibration->reversed); + settings.setValue(deadbndTpl.arg(axis), calibration->deadband); - qCDebug(JoystickLog) << "_saveSettings name:axis:min:max:trim:reversed" + qCDebug(JoystickLog) << "_saveSettings name:axis:min:max:trim:reversed:deadband" << _name << axis << calibration->min << calibration->max << calibration->center - << calibration->reversed; + << calibration->reversed + << calibration->deadband; } for (int function=0; functioncalibration.deadband) valueNormalized-=calibration.deadband; + else if (valueNormalized<-calibration.deadband) valueNormalized+=calibration.deadband; + else valueNormalized = 0.f; + } + float axisPercent = valueNormalized / axisLength; float correctedValue = axisBasis * axisPercent; @@ -208,13 +230,14 @@ float Joystick::_adjustRange(int value, Calibration_t calibration) } #if 0 - qCDebug(JoystickLog) << "_adjustRange corrected:value:min:max:center:reversed:basis:normalized:length" + qCDebug(JoystickLog) << "_adjustRange corrected:value:min:max:center:reversed:deadband:basis:normalized:length" << correctedValue << value << calibration.min << calibration.max << calibration.center - << calibration.center + << calibration.reversed + << calibration.deadband << axisBasis << valueNormalized << axisLength; @@ -265,16 +288,25 @@ void Joystick::run(void) if (_calibrationMode != CalibrationModeCalibrating) { int axis = _rgFunctionAxis[rollFunction]; - float roll = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis]); + float roll = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis], _deadband); axis = _rgFunctionAxis[pitchFunction]; - float pitch = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis]); + float pitch = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis], _deadband); axis = _rgFunctionAxis[yawFunction]; - float yaw = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis]); + float yaw = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis],_deadband); axis = _rgFunctionAxis[throttleFunction]; - float throttle = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis]); + float throttle = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis], _throttleMode==ThrottleModeDownZero?false:_deadband); + + if ( _accumulator ) { + static float throttle_accu = 0.f; + + throttle_accu += throttle*(40/1000.f); //for throttle to change from min to max it will take 1000ms (40ms is a loop time) + + throttle_accu = std::max(static_cast(-1.f), std::min(throttle_accu, static_cast(1.f))); + throttle = throttle_accu; + } float roll_limited = std::max(static_cast(-M_PI_4), std::min(roll, static_cast(M_PI_4))); float pitch_limited = std::max(static_cast(-M_PI_4), std::min(pitch, static_cast(M_PI_4))); @@ -512,6 +544,11 @@ void Joystick::setThrottleMode(int mode) } _throttleMode = (ThrottleMode_t)mode; + + if (_throttleMode == ThrottleModeDownZero) { + setAccumulator(false); + } + _saveSettings(); emit throttleModeChanged(_throttleMode); } @@ -529,6 +566,31 @@ void Joystick::setExponential(bool expo) emit exponentialChanged(_exponential); } +bool Joystick::accumulator(void) +{ + return _accumulator; +} + +void Joystick::setAccumulator(bool accu) +{ + _accumulator = accu; + + _saveSettings(); + emit accumulatorChanged(_accumulator); +} + +bool Joystick::deadband(void) +{ + return _deadband; +} + +void Joystick::setDeadband(bool deadband) +{ + _deadband = deadband; + + _saveSettings(); +} + void Joystick::startCalibrationMode(CalibrationMode_t mode) { if (mode == CalibrationModeOff) { diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index bc32bc6e10d93e0b760a9d5e51172dd58d47a306..c9915eae20d1c7d6d29600948e7e4493cbc7bbc7 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -34,6 +34,7 @@ public: int min; int max; int center; + int deadband; bool reversed; } Calibration_t; @@ -65,7 +66,8 @@ public: Q_INVOKABLE QString getButtonAction(int button); Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged) - Q_PROPERTY(int exponential READ exponential WRITE setExponential NOTIFY exponentialChanged) + Q_PROPERTY(bool exponential READ exponential WRITE setExponential NOTIFY exponentialChanged) + Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged) // Property accessors @@ -93,6 +95,12 @@ public: bool exponential(void); void setExponential(bool expo); + bool accumulator(void); + void setAccumulator(bool accu); + + bool deadband(void); + void setDeadband(bool accu); + typedef enum { CalibrationModeOff, // Not calibrating CalibrationModeMonitor, // Monitors are active, continue to send to vehicle if already polling @@ -118,6 +126,8 @@ signals: void exponentialChanged(bool exponential); + void accumulatorChanged(bool accumulator); + void enabledChanged(bool enabled); /// Signal containing new joystick information @@ -133,7 +143,7 @@ signals: protected: void _saveSettings(void); void _loadSettings(void); - float _adjustRange(int value, Calibration_t calibration); + float _adjustRange(int value, Calibration_t calibration, bool withDeadbands); void _buttonAction(const QString& action); bool _validAxis(int axis); bool _validButton(int button); @@ -175,6 +185,8 @@ protected: ThrottleMode_t _throttleMode; bool _exponential; + bool _accumulator; + bool _deadband; Vehicle* _activeVehicle; bool _pollingStartedForCalibration; @@ -189,6 +201,8 @@ private: static const char* _buttonActionSettingsKey; static const char* _throttleModeSettingsKey; static const char* _exponentialSettingsKey; + static const char* _accumulatorSettingsKey; + static const char* _deadbandSettingsKey; }; #endif diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 81cf9f6a1ad2e7f98bc793a07340d301fcc30ba6..e0567057c0f11d87640cf714117dcab30b5df2ea 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -308,8 +308,8 @@ { "id": 84, "rawName": "MAV_CMD_NAV_VTOL_TAKEOFF", - "friendlyName": "VTOL takeoff", - "description": "Takeoff from ground using VTOL mode.", + "friendlyName": "VTOL takeoff and transition", + "description": "Takeoff in VTOL mode, transition to forward flight and fly to the specified location.", "specifiesCoordinate": true, "friendlyEdit": true, "category": "VTOL", @@ -323,8 +323,8 @@ { "id": 85, "rawName": "MAV_CMD_NAV_VTOL_LAND", - "friendlyName": "VTOL land", - "description": "Land using VTOL mode.", + "friendlyName": "VTOL transition and land", + "description": "Transition to VTOL mode and land.", "specifiesCoordinate": true, "friendlyEdit": true, "category": "VTOL", @@ -975,7 +975,7 @@ "id": 3000, "rawName": "MAV_CMD_DO_VTOL_TRANSITION", "friendlyName": "VTOL Transition", - "description": "Perform flight mode transition", + "description": "Perform flight mode transition.", "category": "VTOL", "param1": { "label": "Mode:", diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml index 45128a08740334b2b172c8a0d02353a8b5a31410..503c6be53598527acd296f3b319db50ffa7afe3c 100644 --- a/src/VehicleSetup/JoystickConfig.qml +++ b/src/VehicleSetup/JoystickConfig.qml @@ -72,7 +72,7 @@ SetupPage { Item { property int axisValue: 0 - + property int deadbandValue: 0 property int __lastAxisValue: 0 readonly property int __axisValueMaxJitter: 100 @@ -87,6 +87,20 @@ SetupPage { color: __barColor } + // Deadband + Rectangle { + id: deadbandBar + anchors.verticalCenter: parent.verticalCenter + x: _deadbandPosition + width: _deadbandWidth + height: parent.height / 2 + color: "#8c161a" + + property real _percentDeadband: ((2 * deadbandValue) / (32768.0 * 2)) + property real _deadbandWidth: parent.width * _percentDeadband + property real _deadbandPosition: (parent.width - _deadbandWidth) / 2 + } + // Center point Rectangle { anchors.horizontalCenter: parent.horizontalCenter @@ -126,13 +140,15 @@ SetupPage { duration: 1500 } - /* + // Axis value debugger + /* QGCLabel { anchors.fill: parent text: axisValue } */ + } } // Component - axisMonitorDisplayComponent @@ -180,6 +196,8 @@ SetupPage { target: controller onRollAxisValueChanged: rollLoader.item.axisValue = value + + onRollAxisDeadbandChanged: rollLoader.item.deadbandValue = value } } @@ -210,6 +228,9 @@ SetupPage { target: controller onPitchAxisValueChanged: pitchLoader.item.axisValue = value + + onPitchAxisDeadbandChanged: pitchLoader.item.deadbandValue = value + } } @@ -240,6 +261,8 @@ SetupPage { target: controller onYawAxisValueChanged: yawLoader.item.axisValue = value + + onYawAxisDeadbandChanged: yawLoader.item.deadbandValue = value } } @@ -270,6 +293,8 @@ SetupPage { target: controller onThrottleAxisValueChanged: throttleLoader.item.axisValue = value + + onThrottleAxisDeadbandChanged: throttleLoader.item.deadbandValue = value } } } // Column - Attitude Control labels @@ -382,6 +407,21 @@ SetupPage { onClicked: _activeJoystick.throttleMode = 0 } + Row { + x: 20 + width: parent.width + spacing: ScreenTools.defaultFontPixelWidth + visible: _activeJoystick.throttleMode == 0 + + QGCCheckBox { + id: accumulator + checked: _activeJoystick.accumulator + text: qsTr("Spring loaded throttle smoothing") + + onClicked: _activeJoystick.accumulator = checked + } + } + QGCRadioButton { exclusiveGroup: throttleModeExclusiveGroup text: qsTr("Full down stick is zero throttle") @@ -435,6 +475,20 @@ SetupPage { onActivated: _activeVehicle.joystickMode = index } } + + Row { + width: parent.width + spacing: ScreenTools.defaultFontPixelWidth + visible: advancedSettings.checked + + QGCCheckBox { + id: deadband + checked: controller.deadbandToggle + text: qsTr("Deadbands") + + onClicked: controller.deadbandToggle = checked + } + } } } // Column - left column @@ -697,3 +751,5 @@ SetupPage { } // Item } // Component - pageComponent } // SetupPage + + diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc index 81da51b91ba5d7869f478b18628ee47934efc84d..505478bd73107da3be0fe2dba60b4ea689a059d8 100644 --- a/src/VehicleSetup/JoystickConfigController.cc +++ b/src/VehicleSetup/JoystickConfigController.cc @@ -210,6 +210,18 @@ void JoystickConfigController::cancelButtonClicked(void) _stopCalibration(); } +bool JoystickConfigController::getDeadbandToggle() { + return _activeJoystick->deadband(); +} + +void JoystickConfigController::setDeadbandToggle(bool deadband) { + _activeJoystick->setDeadband(deadband); + + _signalAllAttiudeValueChanges(); + + emit deadbandToggled(deadband); +} + void JoystickConfigController::_saveAllTrims(void) { // We save all trims as the first step. At this point no axes are mapped but it should still @@ -224,16 +236,28 @@ void JoystickConfigController::_saveAllTrims(void) _advanceState(); } +void JoystickConfigController::_axisDeadbandChanged(int axis, int value) +{ + value = abs(value)<_calValidMaxValue?abs(value):_calValidMaxValue; + + _rgAxisInfo[axis].deadband = value; + + qCDebug(JoystickConfigControllerLog) << "Axis:" << axis << "Deadband:" << _rgAxisInfo[axis].deadband; +} + /// @brief Waits for the sticks to be centered, enabling Next when done. void JoystickConfigController::_inputCenterWaitBegin(Joystick::AxisFunction_t function, int axis, int value) { Q_UNUSED(function); - Q_UNUSED(axis); - Q_UNUSED(value); - - // FIXME: Doesn't wait for center - + + //sensing deadband + if (abs(value)*1.1f>_rgAxisInfo[axis].deadband) { //add 10% on top of existing deadband + _axisDeadbandChanged(axis,abs(value)*1.1f); + } + _nextButton->setEnabled(true); + + // FIXME: Doesn't wait for center } bool JoystickConfigController::_stickSettleComplete(int axis, int value) @@ -420,6 +444,7 @@ void JoystickConfigController::_resetInternalCalibrationValues(void) struct AxisInfo* info = &_rgAxisInfo[i]; info->function = Joystick::maxFunction; info->reversed = false; + info->deadband = 0; info->axisMin = JoystickConfigController::_calCenterPoint; info->axisMax = JoystickConfigController::_calCenterPoint; info->axisTrim = JoystickConfigController::_calCenterPoint; @@ -457,7 +482,8 @@ void JoystickConfigController::_setInternalCalibrationValuesFromSettings(void) info->axisMin = calibration.min; info->axisMax = calibration.max; info->reversed = calibration.reversed; - + info->deadband = calibration.deadband; + qCDebug(JoystickConfigControllerLog) << "Read settings name:axis:min:max:trim:reversed" << joystick->name() << axis << info->axisMin << info->axisMax << info->axisTrim << info->reversed; } @@ -512,6 +538,7 @@ void JoystickConfigController::_validateCalibration(void) info->axisMin = _calDefaultMinValue; info->axisMax = _calDefaultMaxValue; info->axisTrim = info->axisMin + ((info->axisMax - info->axisMin) / 2); + info->deadband = 0; info->reversed = false; } } @@ -534,6 +561,7 @@ void JoystickConfigController::_writeCalibration(void) calibration.min = info->axisMin; calibration.max = info->axisMax; calibration.reversed = info->reversed; + calibration.deadband = info->deadband; joystick->setCalibration(axis, calibration); } @@ -664,6 +692,42 @@ int JoystickConfigController::throttleAxisValue(void) } } +int JoystickConfigController::rollAxisDeadband(void) +{ + if ((_rgFunctionAxisMapping[Joystick::rollFunction] != _axisNoAxis) && (_activeJoystick->deadband())) { + return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::rollFunction]].deadband; + } else { + return 0; + } +} + +int JoystickConfigController::pitchAxisDeadband(void) +{ + if ((_rgFunctionAxisMapping[Joystick::pitchFunction] != _axisNoAxis) && (_activeJoystick->deadband())) { + return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::pitchFunction]].deadband; + } else { + return 0; + } +} + +int JoystickConfigController::yawAxisDeadband(void) +{ + if ((_rgFunctionAxisMapping[Joystick::yawFunction] != _axisNoAxis) && (_activeJoystick->deadband())) { + return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::yawFunction]].deadband; + } else { + return 0; + } +} + +int JoystickConfigController::throttleAxisDeadband(void) +{ + if ((_rgFunctionAxisMapping[Joystick::throttleFunction] != _axisNoAxis) && (_activeJoystick->deadband())) { + return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::throttleFunction]].deadband; + } else { + return 0; + } +} + bool JoystickConfigController::rollAxisMapped(void) { return _rgFunctionAxisMapping[Joystick::rollFunction] != _axisNoAxis; @@ -731,6 +795,11 @@ void JoystickConfigController::_signalAllAttiudeValueChanges(void) emit pitchAxisReversedChanged(pitchAxisReversed()); emit yawAxisReversedChanged(yawAxisReversed()); emit throttleAxisReversedChanged(throttleAxisReversed()); + + emit rollAxisDeadbandChanged(rollAxisDeadband()); + emit pitchAxisDeadbandChanged(pitchAxisDeadband()); + emit yawAxisDeadbandChanged(yawAxisDeadband()); + emit throttleAxisDeadbandChanged(throttleAxisDeadband()); } void JoystickConfigController::_activeJoystickChanged(Joystick* joystick) diff --git a/src/VehicleSetup/JoystickConfigController.h b/src/VehicleSetup/JoystickConfigController.h index 231a130e717934a6f3ac0a41142f06012bed22e7..9b0a8c8795a502a0021138d8eb97724eee298939 100644 --- a/src/VehicleSetup/JoystickConfigController.h +++ b/src/VehicleSetup/JoystickConfigController.h @@ -51,29 +51,41 @@ public: Q_PROPERTY(bool pitchAxisMapped READ pitchAxisMapped NOTIFY pitchAxisMappedChanged) Q_PROPERTY(bool yawAxisMapped READ yawAxisMapped NOTIFY yawAxisMappedChanged) Q_PROPERTY(bool throttleAxisMapped READ throttleAxisMapped NOTIFY throttleAxisMappedChanged) - + Q_PROPERTY(int rollAxisValue READ rollAxisValue NOTIFY rollAxisValueChanged) Q_PROPERTY(int pitchAxisValue READ pitchAxisValue NOTIFY pitchAxisValueChanged) Q_PROPERTY(int yawAxisValue READ yawAxisValue NOTIFY yawAxisValueChanged) Q_PROPERTY(int throttleAxisValue READ throttleAxisValue NOTIFY throttleAxisValueChanged) - + + Q_PROPERTY(int rollAxisDeadband READ rollAxisDeadband NOTIFY rollAxisDeadbandChanged) + Q_PROPERTY(int pitchAxisDeadband READ pitchAxisDeadband NOTIFY pitchAxisDeadbandChanged) + Q_PROPERTY(int yawAxisDeadband READ yawAxisDeadband NOTIFY yawAxisDeadbandChanged) + Q_PROPERTY(int throttleAxisDeadband READ throttleAxisDeadband NOTIFY throttleAxisDeadbandChanged) + Q_PROPERTY(int rollAxisReversed READ rollAxisReversed NOTIFY rollAxisReversedChanged) Q_PROPERTY(int pitchAxisReversed READ pitchAxisReversed NOTIFY pitchAxisReversedChanged) Q_PROPERTY(int yawAxisReversed READ yawAxisReversed NOTIFY yawAxisReversedChanged) Q_PROPERTY(int throttleAxisReversed READ throttleAxisReversed NOTIFY throttleAxisReversedChanged) + Q_PROPERTY(bool deadbandToggle READ getDeadbandToggle WRITE setDeadbandToggle NOTIFY deadbandToggled) + Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged) Q_INVOKABLE void cancelButtonClicked(void); Q_INVOKABLE void skipButtonClicked(void); Q_INVOKABLE void nextButtonClicked(void); Q_INVOKABLE void start(void); - + int rollAxisValue(void); int pitchAxisValue(void); int yawAxisValue(void); int throttleAxisValue(void); - + + int rollAxisDeadband(void); + int pitchAxisDeadband(void); + int yawAxisDeadband(void); + int throttleAxisDeadband(void); + bool rollAxisMapped(void); bool pitchAxisMapped(void); bool yawAxisMapped(void); @@ -84,11 +96,14 @@ public: bool yawAxisReversed(void); bool throttleAxisReversed(void); + bool getDeadbandToggle(void); + void setDeadbandToggle(bool); + int axisCount(void); signals: void axisValueChanged(int axis, int value); - + void rollAxisMappedChanged(bool mapped); void pitchAxisMappedChanged(bool mapped); void yawAxisMappedChanged(bool mapped); @@ -98,11 +113,18 @@ signals: void pitchAxisValueChanged(int value); void yawAxisValueChanged(int value); void throttleAxisValueChanged(int value); - + + void rollAxisDeadbandChanged(int value); + void pitchAxisDeadbandChanged(int value); + void yawAxisDeadbandChanged(int value); + void throttleAxisDeadbandChanged(int value); + void rollAxisReversedChanged(bool reversed); void pitchAxisReversedChanged(bool reversed); void yawAxisReversedChanged(bool reversed); void throttleAxisReversedChanged(bool reversed); + + void deadbandToggled(bool value); void imageHelpChanged(QString source); @@ -112,6 +134,7 @@ signals: private slots: void _activeJoystickChanged(Joystick* joystick); void _axisValueChanged(int axis, int value); + void _axisDeadbandChanged(int axis, int value); private: /// @brief The states of the calibration state machine. @@ -144,6 +167,7 @@ private: int axisMin; ///< Minimum axis value int axisMax; ///< Maximum axis value int axisTrim; ///< Trim position + int deadband; ///< Deadband }; Joystick* _activeJoystick; diff --git a/src/qgcunittest/UnitTestList.cc b/src/qgcunittest/UnitTestList.cc index 23b28f6ab8154c7f8c5aec6beb079889d5a80bf1..d0c70f8a760ae704cd015dca89260991197a6799 100644 --- a/src/qgcunittest/UnitTestList.cc +++ b/src/qgcunittest/UnitTestList.cc @@ -47,7 +47,6 @@ UT_REGISTER_TEST(MissionControllerTest) UT_REGISTER_TEST(MissionManagerTest) UT_REGISTER_TEST(RadioConfigTest) UT_REGISTER_TEST(TCPLinkTest) -UT_REGISTER_TEST(FileManagerTest) UT_REGISTER_TEST(ParameterManagerTest) UT_REGISTER_TEST(MissionCommandTreeTest) UT_REGISTER_TEST(LogDownloadTest) @@ -58,3 +57,6 @@ UT_REGISTER_TEST(LogDownloadTest) // FIXME: Temporarily disabled until this can be stabilized //UT_REGISTER_TEST(MainWindowTest) +// Onboard file support has been removed until it can be make to work correctly +//UT_REGISTER_TEST(FileManagerTest) + diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index c753209ffc57e2235a1e4dae77ee925ca48d5639..4435feddbe9ed20dd7f5ada60604920ec3f532e7 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -301,12 +301,17 @@ void MainWindow::_buildCommonWidgets(void) logPlayer = new QGCMAVLinkLogPlayer(statusBar()); statusBar()->addPermanentWidget(logPlayer); + // Populate widget menu for (int i = 0, end = ARRAY_SIZE(rgDockWidgetNames); i < end; i++) { + if (i == ONBOARD_FILES) { + // Temporarily removed until twe can fix all the problems with it + continue; + } const char* pDockWidgetName = rgDockWidgetNames[i]; // Add to menu - QAction* action = new QAction(tr(pDockWidgetName), this); + QAction* action = new QAction(pDockWidgetName, this); action->setCheckable(true); action->setData(i); connect(action, &QAction::triggered, this, &MainWindow::_showDockWidgetAction); @@ -318,6 +323,11 @@ void MainWindow::_buildCommonWidgets(void) /// Shows or hides the specified dock widget, creating if necessary void MainWindow::_showDockWidget(const QString& name, bool show) { + if (name == rgDockWidgetNames[ONBOARD_FILES]) { + // Temporarily disabled due to bugs + return; + } + // Create the inner widget if we need to if (!_mapName2DockWidget.contains(name)) { if(!_createInnerDockWidget(name)) { diff --git a/src/ui/toolbar/MainToolBar.qml b/src/ui/toolbar/MainToolBar.qml index f8b4170e9401d66c4d2e1d38caee9b0e54b1e227..c8603706776a9ab9382487015d5a2c4fd92ce8a0 100644 --- a/src/ui/toolbar/MainToolBar.qml +++ b/src/ui/toolbar/MainToolBar.qml @@ -393,6 +393,7 @@ Rectangle { property bool vehicleConnectionLost: activeVehicle ? activeVehicle.connectionLost : false Loader { + id: indicatorLoader source: activeVehicle && !parent.vehicleConnectionLost ? "MainToolBarIndicators.qml" : "" anchors.left: parent.left anchors.verticalCenter: parent.verticalCenter @@ -408,7 +409,6 @@ Rectangle { anchors.right: disconnectButton.left anchors.verticalCenter: parent.verticalCenter visible: parent.vehicleConnectionLost - } QGCButton { @@ -427,7 +427,7 @@ Rectangle { anchors.right: parent.right anchors.top: parent.top anchors.bottom: parent.bottom - visible: parent.x < x && !disconnectButton.visible && source != "" + visible: x > indicatorLoader.x + indicatorLoader.width && !disconnectButton.visible && source != "" fillMode: Image.PreserveAspectFit source: activeVehicle ? activeVehicle.brandImage : "" }