From ec4bb916300a9ea2537f8f39b106b57dfc971e68 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 27 Oct 2020 11:32:22 -0700 Subject: [PATCH] FTP Manager rewrite, COMPONENT_INFORMATION fixes (#9139) * Use correct key names * Rewrite FTPManager * Fix Reset Session at end of download * Fixes for metadata download --- src/Vehicle/CompInfoParam.cc | 4 +- src/Vehicle/ComponentInformationManager.cc | 30 +- src/Vehicle/FTPManager.cc | 1023 ++--- src/Vehicle/FTPManager.h | 142 +- src/Vehicle/FTPManagerTest.cc | 5 + src/Vehicle/FTPManagerTest.h | 3 + src/Vehicle/Vehicle.cc | 2 +- src/comm/MockLink.Parameter.MetaData.json | 4740 ++++++++++---------- src/comm/MockLinkFTP.cc | 13 +- 9 files changed, 2830 insertions(+), 3132 deletions(-) diff --git a/src/Vehicle/CompInfoParam.cc b/src/Vehicle/CompInfoParam.cc index 7a619ef91..9b56cd475 100644 --- a/src/Vehicle/CompInfoParam.cc +++ b/src/Vehicle/CompInfoParam.cc @@ -31,8 +31,10 @@ CompInfoParam::CompInfoParam(uint8_t compId, Vehicle* vehicle, QObject* parent) } -void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString& /*translationJsonFileName*/) +void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString& translationJsonFileName) { + qCDebug(CompInfoParamLog) << "setJson: metadataJsonFileName:translationJsonFileName" << metadataJsonFileName << translationJsonFileName; + if (metadataJsonFileName.isEmpty()) { // This will fall back to using the old FirmwarePlugin mechanism for parameter meta data. // In this case paramter metadata is loaded through the _parameterMajorVersionKnown call which happens after parameter are downloaded diff --git a/src/Vehicle/ComponentInformationManager.cc b/src/Vehicle/ComponentInformationManager.cc index b547a489d..8dae037ce 100644 --- a/src/Vehicle/ComponentInformationManager.cc +++ b/src/Vehicle/ComponentInformationManager.cc @@ -215,8 +215,9 @@ QString RequestMetaDataTypeStateMachine::_downloadCompleteJsonWorker(const QStri void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson(const QString& fileName, const QString& errorMsg) { - qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson fileName:errorMsg" << fileName << errorMsg; + qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson fileName:errorMsg" << fileName << errorMsg; + disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson); if (errorMsg.isEmpty()) { _jsonMetadataFileName = _downloadCompleteJsonWorker(fileName, "metadata.json"); } @@ -226,15 +227,15 @@ void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson(const QSt void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson(const QString& fileName, const QString& errorMsg) { - qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson fileName:errorMsg" << fileName << errorMsg; - QString jsonTranslationFileName; + + qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson fileName:errorMsg" << fileName << errorMsg; + + disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson); if (errorMsg.isEmpty()) { - jsonTranslationFileName = _downloadCompleteJsonWorker(fileName, "translation.json"); + _jsonTranslationFileName = _downloadCompleteJsonWorker(fileName, "translation.json"); } - _compInfo->setJson(_jsonMetadataFileName, jsonTranslationFileName); - advance(); } @@ -242,6 +243,7 @@ void RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson(QString { qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg; + disconnect(qobject_cast(sender()), &QGCFileDownload::downloadComplete, this, &RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson); if (errorMsg.isEmpty()) { _jsonMetadataFileName = _downloadCompleteJsonWorker(localFile, "metadata.json"); } @@ -251,15 +253,15 @@ void RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson(QString void RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson(QString remoteFile, QString localFile, QString errorMsg) { + QString jsonTranslationFileName; + qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg; - QString jsonTranslationFileName; + disconnect(qobject_cast(sender()), &QGCFileDownload::downloadComplete, this, &RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson); if (errorMsg.isEmpty()) { - jsonTranslationFileName = _downloadCompleteJsonWorker(localFile, "translation.json"); + _jsonTranslationFileName = _downloadCompleteJsonWorker(localFile, "translation.json"); } - _compInfo->setJson(_jsonMetadataFileName, jsonTranslationFileName); - advance(); } @@ -318,6 +320,14 @@ void RequestMetaDataTypeStateMachine::_stateRequestComplete(StateMachine* stateM CompInfo* compInfo = requestMachine->compInfo(); compInfo->setJson(requestMachine->_jsonMetadataFileName, requestMachine->_jsonTranslationFileName); + + if (!requestMachine->_jsonMetadataFileName.isEmpty()) { + QFile(requestMachine->_jsonMetadataFileName).remove(); + } + if (!requestMachine->_jsonTranslationFileName.isEmpty()) { + QFile(requestMachine->_jsonTranslationFileName).remove(); + } + requestMachine->advance(); } diff --git a/src/Vehicle/FTPManager.cc b/src/Vehicle/FTPManager.cc index f64ba2b0a..ad32e2e51 100644 --- a/src/Vehicle/FTPManager.cc +++ b/src/Vehicle/FTPManager.cc @@ -7,7 +7,6 @@ * ****************************************************************************/ - #include "FTPManager.h" #include "QGC.h" #include "MAVLinkProtocol.h" @@ -24,97 +23,66 @@ FTPManager::FTPManager(Vehicle* vehicle) : QObject (vehicle) , _vehicle (vehicle) { - _ackTimer.setSingleShot(true); - if (qgcApp()->runningUnitTests()) { - // Mock link responds immediately if at all - _ackTimer.setInterval(10); - } else { - _ackTimer.setInterval(_ackTimerTimeoutMsecs); - } - connect(&_ackTimer, &QTimer::timeout, this, &FTPManager::_ackTimeout); - - _lastOutgoingRequest.hdr.seqNumber = 0; + _ackOrNakTimeoutTimer.setSingleShot(true); + // Mock link responds immediately if at all, speed up unit tests with faster timoue + _ackOrNakTimeoutTimer.setInterval(qgcApp()->runningUnitTests() ? 10 : _ackOrNakTimeoutMsecs); + connect(&_ackOrNakTimeoutTimer, &QTimer::timeout, this, &FTPManager::_ackOrNakTimeout); // Make sure we don't have bad structure packing Q_ASSERT(sizeof(MavlinkFTP::RequestHeader) == 12); } -void FTPManager::_handlOpenFileROAck(MavlinkFTP::Request* ack) +bool FTPManager::download(const QString& from, const QString& toDir) { - qCDebug(FTPManagerLog) << QString("_handlOpenFileROAck: _waitState(%1) _readFileLength(%3)").arg(MavlinkFTP::opCodeToString(_waitState)).arg(ack->openFileLength); - - if (_waitState != MavlinkFTP::kCmdOpenFileRO) { - qCDebug(FTPManagerLog) << "Received OpenFileRO Ack while not waiting for it"; - return; + qCDebug(FTPManagerLog) << "download from:" << from << "to:" << toDir; + + if (!_rgStateMachine.isEmpty()) { + qCDebug(FTPManagerLog) << "Cannot download. Already in another operation"; + return false; } - if (ack->hdr.size != sizeof(uint32_t)) { - qCDebug(FTPManagerLog) << "_handlOpenFileROAck: ack->hdr.size != sizeof(uint32_t)" << ack->hdr.size << sizeof(uint32_t); - _downloadComplete(tr("Download failed")); - return; + static const StateFunctions_t rgDownloadStateMachine[] = { + { &FTPManager::_openFileROBegin, &FTPManager::_openFileROAckOrNak, &FTPManager::_openFileROTimeout }, + { &FTPManager::_burstReadFileBegin, &FTPManager::_burstReadFileAckOrNak, &FTPManager::_burstReadFileTimeout }, + { &FTPManager::_fillMissingBlocksBegin, &FTPManager::_fillMissingBlocksAckOrNak, &FTPManager::_fillMissingBlocksTimeout }, + { &FTPManager::_resetSessionsBegin, &FTPManager::_resetSessionsAckOrNak, &FTPManager::_resetSessionsTimeout }, + { &FTPManager::_downloadCompleteNoError, nullptr, nullptr }, + }; + for (size_t i=0; ihdr.session; - _downloadState.fileSize = ack->openFileLength; - _downloadState.expectedBurstOffset = 0; - - _downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName)); - if (!_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) { - qCDebug(FTPManagerLog) << "_handlOpenFileROAck: _downloadState.file open failed" << _downloadState.file.errorString(); - _downloadComplete(tr("Download failed")); - return; + QString ftpPrefix("mavlinkftp://"); + if (from.startsWith(ftpPrefix, Qt::CaseInsensitive)) { + _downloadState.fullPathOnVehicle = from.right(from.length() - ftpPrefix.length() + 1); + } else { + _downloadState.fullPathOnVehicle = from; } - MavlinkFTP::Request request; - request.hdr.session = _activeSession; - request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile; - request.hdr.offset = _downloadState.expectedBurstOffset; - request.hdr.size = sizeof(request.data); - _sendRequestExpectAck(&request); -} - -void FTPManager::_requestMissingBurstData() -{ - MavlinkFTP::Request request; - - if (_downloadState.missingData.count()) { - MissingData_t& missingData = _downloadState.missingData.first(); - - uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytes); + // We need to strip off the file name from the fully qualified path. We can't use the usual QDir + // routines because this path does not exist locally. + int lastDirSlashIndex; + for (lastDirSlashIndex=_downloadState.fullPathOnVehicle.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) { + if (_downloadState.fullPathOnVehicle[lastDirSlashIndex] == '/') { + break; + } + } + lastDirSlashIndex++; // move past slash - qCDebug(FTPManagerLog) << "_requestMissingBurstData: offset:cBytesToRead" << missingData.offset << cBytesToRead; + _downloadState.fileName = _downloadState.fullPathOnVehicle.right(_downloadState.fullPathOnVehicle.size() - lastDirSlashIndex); - request.hdr.session = _activeSession; - request.hdr.opcode = MavlinkFTP::kCmdReadFile; - request.hdr.offset = missingData.offset; - request.hdr.size = cBytesToRead; - _waitState = MavlinkFTP::kCmdReadFile; - _downloadState.retryCount = 0; - _downloadState.expectedReadOffset = request.hdr.offset; + qDebug() << _downloadState.fullPathOnVehicle << _downloadState.fileName; - if (cBytesToRead < missingData.cBytes) { - missingData.offset += cBytesToRead; - missingData.cBytes -= cBytesToRead; - } else { - _downloadState.missingData.takeFirst(); - } - } else { - qCDebug(FTPManagerLog) << "_requestMissingBurstData: starting next burst" << _downloadState.expectedBurstOffset; - request.hdr.session = _activeSession; - request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile; - request.hdr.offset = _downloadState.expectedBurstOffset; - request.hdr.size = sizeof(request.data); - _waitState = MavlinkFTP::kCmdBurstReadFile; - } + _startStateMachine(); - _sendRequestExpectAck(&request); + return true; } /// Closes out a download session by writing the file and doing cleanup. -/// @param success true: successful download completion, false: error during download +/// @param errorMsg Error message, empty if no error void FTPManager::_downloadComplete(const QString& errorMsg) { qCDebug(FTPManagerLog) << QString("_downloadComplete: errorMsg(%1)").arg(errorMsg); @@ -122,698 +90,433 @@ void FTPManager::_downloadComplete(const QString& errorMsg) QString downloadFilePath = _downloadState.toDir.absoluteFilePath(_downloadState.fileName); QString error = errorMsg; - _ackTimer.stop(); - _waitState = MavlinkFTP::kCmdNone; - - if (error.isEmpty()) { + _ackOrNakTimeoutTimer.stop(); + _rgStateMachine.clear(); + _currentStateMachineIndex = -1; + if (_downloadState.file.isOpen()) { _downloadState.file.close(); + if (!errorMsg.isEmpty()) { + _downloadState.file.remove(); + } } - - _downloadState.reset(); - _sendResetCommand(); // Close the open session - emit downloadComplete(downloadFilePath, error); -} -/// Closes out an upload session doing cleanup. -/// @param success true: successful upload completion, false: error during download -void FTPManager::_uploadComplete(const QString& errorMsg) -{ - qCDebug(FTPManagerLog) << QString("_uploadComplete: errorMsg(%1)").arg(errorMsg); - - _waitState = MavlinkFTP::kCmdNone; - _writeFileSize = 0; - _writeFileAccumulator.clear(); - _sendResetCommand(); - emit uploadComplete(errorMsg); + emit downloadComplete(downloadFilePath, errorMsg); } -// We only do read files to fill in holes from a burst read -void FTPManager::_handleReadFileAck(MavlinkFTP::Request* ack) +void FTPManager::_mavlinkMessageReceived(const mavlink_message_t& message) { - if (ack->hdr.session != _activeSession) { - return; - } - - qCDebug(FTPManagerLog) << "_handleReadFileAck: offset:size" << ack->hdr.offset << ack->hdr.size; - - if (ack->hdr.offset != _downloadState.expectedReadOffset) { - if (++_downloadState.retryCount > _maxRetry) { - qCDebug(FTPManagerLog) << QString("_handleReadFileAck: retries exceeded"); - _downloadComplete(tr("Download failed: Unable to retrieve specified file contents")); - return; - } - - // Ask for current offset again - qCDebug(FTPManagerLog) << QString("_handleReadFileAck: retry retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedReadOffset); - MavlinkFTP::Request request; - request.hdr.session = _activeSession; - request.hdr.opcode = _waitState; - request.hdr.offset = _downloadState.expectedReadOffset; - request.hdr.size = 0; - _sendRequestExpectAck(&request); + if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return; } - _downloadState.file.seek(ack->hdr.offset); - int bytesWritten = _downloadState.file.write((const char*)ack->data, ack->hdr.size); - if (bytesWritten != ack->hdr.size) { - _downloadComplete(tr("Download failed: Error saving file")); + if (_currentStateMachineIndex == -1) { return; } - _downloadState.bytesWritten += ack->hdr.size; - - if (_downloadState.fileSize != 0) { - emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize)); - } - // Move on to fill in possible next hole - _requestMissingBurstData(); -} + mavlink_file_transfer_protocol_t data; + mavlink_msg_file_transfer_protocol_decode(&message, &data); -void FTPManager::_handleBurstReadFileAck(MavlinkFTP::Request* ack) -{ - if (ack->hdr.session != _activeSession) { + // Make sure we are the target system + int qgcId = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(); + if (data.target_system != qgcId) { return; } + + MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0]; - qCDebug(FTPManagerLog) << QString("_handleBurstReadFileAck: offset(%1) size(%2) burstComplete(%3)").arg(ack->hdr.offset).arg(ack->hdr.size).arg(ack->hdr.burstComplete); - - if (ack->hdr.offset != _downloadState.expectedBurstOffset) { - if (ack->hdr.offset > _downloadState.expectedBurstOffset) { - MissingData_t missingData; - missingData.offset = _downloadState.expectedBurstOffset; - missingData.cBytes = ack->hdr.offset - _downloadState.expectedBurstOffset; - _downloadState.missingData.append(missingData); - qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: adding missing data offset:cBytes" << missingData.offset << missingData.cBytes; - } else { - qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: received offset less than expected offset received:expected" << ack->hdr.offset << _downloadState.expectedBurstOffset; - _ackTimer.start(); - return; - } - } + // Ignore old/reordered packets (handle wrap-around properly) + uint16_t actualIncomingSeqNumber = request->hdr.seqNumber; + if ((uint16_t)((_expectedIncomingSeqNumber - 1) - actualIncomingSeqNumber) < (std::numeric_limits::max()/2)) { + qCDebug(FTPManagerLog) << "_mavlinkMessageReceived: Received old packet seqNum expected:actual" << _expectedIncomingSeqNumber << actualIncomingSeqNumber + << "hdr.opcode:hdr.req_opcode" << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast(request->hdr.req_opcode)); - _downloadState.file.seek(ack->hdr.offset); - int bytesWritten = _downloadState.file.write((const char*)ack->data, ack->hdr.size); - if (bytesWritten != ack->hdr.size) { - _downloadComplete(tr("Download failed: Error saving file")); return; } - _downloadState.bytesWritten += ack->hdr.size; - _downloadState.expectedBurstOffset = ack->hdr.offset + ack->hdr.size; - if (_downloadState.fileSize != 0) { - emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize)); - } + qCDebug(FTPManagerLog) << "_mavlinkMessageReceived: hdr.opcode:hdr.req_opcode:seqNumber" + << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast(request->hdr.req_opcode)) + << request->hdr.seqNumber; - if (ack->hdr.burstComplete) { - _requestMissingBurstData(); - } else { - // Still within a burst, next ack should come automatically - _ackTimer.start(); - } + (this->*_rgStateMachine[_currentStateMachineIndex].ackNakFn)(request); } -void FTPManager::_listAckResponse(MavlinkFTP::Request* /*listAck*/) +void FTPManager::_startStateMachine(void) { -#if 0 - if (listAck->hdr.offset != _listOffset) { - // this is a real error (directory listing is synchronous), no need to retransmit - _currentOperation = kCOIdle; - _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset)); - return; - } - - uint8_t offset = 0; - uint8_t cListEntries = 0; - uint8_t cBytes = listAck->hdr.size; - - // parse filenames out of the buffer - while (offset < cBytes) { - const char * ptr = ((const char *)listAck->data) + offset; + _currentStateMachineIndex = -1; + _advanceStateMachine(); +} - // get the length of the name - uint8_t cBytesLeft = cBytes - offset; - uint8_t nlen = static_cast(strnlen(ptr, cBytesLeft)); - if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) { - _currentOperation = kCOIdle; - _emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr)); - return; - } else if (nlen == cBytesLeft) { - _currentOperation = kCOIdle; - _emitErrorMessage(tr("Missing NULL termination in list entry")); - return; - } +void FTPManager::_advanceStateMachine(void) +{ + _currentStateMachineIndex++; + (this->*_rgStateMachine[_currentStateMachineIndex].beginFn)(); +} - // Returned names are prepended with D for directory, F for file, S for skip - if (*ptr == 'F' || *ptr == 'D') { - // put it in the view - _emitListEntry(ptr); - } else if (*ptr == 'S') { - // do nothing - } else { - qDebug() << "unknown entry" << ptr; - } +void FTPManager::_ackOrNakTimeout(void) +{ + (this->*_rgStateMachine[_currentStateMachineIndex].timeoutFn)(); +} - // account for the name + NUL - offset += nlen + 1; +void FTPManager::_fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str) +{ + strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data)); + request->hdr.size = static_cast(strnlen((const char *)&request->data[0], sizeof(request->data))); +} - cListEntries++; - } +QString FTPManager::_errorMsgFromNak(const MavlinkFTP::Request* nak) +{ + QString errorMsg; + MavlinkFTP::ErrorCode_t errorCode = static_cast(nak->data[0]); - if (listAck->hdr.size == 0 || cListEntries == 0) { - // Directory is empty, we're done - Q_ASSERT(listAck->hdr.opcode == MavlinkFTP::kRspAck); - _currentOperation = kCOIdle; - emit commandComplete(); + // Nak's normally have 1 byte of data for error code, except for MavlinkFTP::kErrFailErrno which has additional byte for errno + if ((errorCode == MavlinkFTP::kErrFailErrno && nak->hdr.size != 2) || ((errorCode != MavlinkFTP::kErrFailErrno) && nak->hdr.size != 1)) { + errorMsg = tr("Invalid Nak format"); + } else if (errorCode == MavlinkFTP::kErrFailErrno) { + errorMsg = tr("errno %1").arg(nak->data[1]); } else { - // Possibly more entries to come, need to keep trying till we get EOF - _currentOperation = kCOList; - _listOffset += cListEntries; - _sendListCommand(); + errorMsg = MavlinkFTP::errorCodeToString(errorCode); } -#endif + + return errorMsg; } -/// @brief Respond to the Ack associated with the create command. -void FTPManager::_createAckResponse(MavlinkFTP::Request* /*createAck*/) +void FTPManager::_openFileROBegin(void) { -#if 0 - qCDebug(FTPManagerLog) << "_createAckResponse"; - - _currentOperation = kCOWrite; - _activeSession = createAck->hdr.session; - - // Start the sequence of write commands from the beginning of the file + MavlinkFTP::Request request; + request.hdr.session = 0; + request.hdr.opcode = MavlinkFTP::kCmdOpenFileRO; + request.hdr.offset = 0; + request.hdr.size = 0; + _fillRequestDataWithString(&request, _downloadState.fullPathOnVehicle); + _sendRequestExpectAck(&request); +} - _writeOffset = 0; - _writeSize = 0; - - _writeFileDatablock(); -#endif +void FTPManager::_openFileROTimeout(void) +{ + qCDebug(FTPManagerLog) << "_openFileROTimeout"; + _downloadComplete(tr("Download failed")); } -/// @brief Respond to the Ack associated with the write command. -void FTPManager::_writeAckResponse(MavlinkFTP::Request* /*writeAck*/) +void FTPManager::_openFileROAckOrNak(const MavlinkFTP::Request* ackOrNak) { -#if 0 - if(_writeOffset + _writeSize >= _writeFileSize){ - _closeUploadSession(true /* success */); + MavlinkFTP::OpCode_t requestOpCode = static_cast(ackOrNak->hdr.req_opcode); + if (requestOpCode != MavlinkFTP::kCmdOpenFileRO) { + qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode); return; } - - if (writeAck->hdr.session != _activeSession) { - _closeUploadSession(false /* failure */); - _emitErrorMessage(tr("Write: Incorrect session returned")); + if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) { + qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber; return; } - if (writeAck->hdr.offset != _writeOffset) { - _closeUploadSession(false /* failure */); - _emitErrorMessage(tr("Write: Offset returned (%1) differs from offset requested (%2)").arg(writeAck->hdr.offset).arg(_writeOffset)); - return; - } + _ackOrNakTimeoutTimer.stop(); - if (writeAck->hdr.size != sizeof(uint32_t)) { - _closeUploadSession(false /* failure */); - _emitErrorMessage(tr("Write: Returned invalid size of write size data")); - return; - } + if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) { + qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack - sessionId:openFileLength" << ackOrNak->hdr.session << ackOrNak->openFileLength; + if (ackOrNak->hdr.size != sizeof(uint32_t)) { + qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack ack->hdr.size != sizeof(uint32_t)" << ackOrNak->hdr.size << sizeof(uint32_t); + _downloadComplete(tr("Download failed")); + return; + } - if( writeAck->writeFileLength !=_writeSize) { - _closeUploadSession(false /* failure */); - _emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize)); - return; - } + _downloadState.sessionId = ackOrNak->hdr.session; + _downloadState.fileSize = ackOrNak->openFileLength; + _downloadState.expectedOffset = 0; - _writeFileDatablock(); -#endif + _downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName)); + if (_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) { + _advanceStateMachine(); + } else { + qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack _downloadState.file open failed" << _downloadState.file.errorString(); + _downloadComplete(tr("Download failed")); + } + } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) { + qCDebug(FTPManagerLog) << "_handlOpenFileROAck: Nak -" << _errorMsgFromNak(ackOrNak); + _downloadComplete(tr("Download failed")); + } } -/// @brief Send next write file data block. -void FTPManager::_writeFileDatablock(void) +void FTPManager::_burstReadFileWorker(bool firstRequest) { -#if 0 - if (_writeOffset + _writeSize >= _writeFileSize){ - _closeUploadSession(true /* success */); - return; - } - - _writeOffset += _writeSize; + qCDebug(FTPManagerLog) << "_burstReadFileWorker: starting burst at offset:firstRequest:retryCount" << _downloadState.expectedOffset << firstRequest << _downloadState.retryCount; MavlinkFTP::Request request; - request.hdr.session = _activeSession; - request.hdr.opcode = MavlinkFTP::kCmdWriteFile; - request.hdr.offset = _writeOffset; - - if(_writeFileSize -_writeOffset > sizeof(request.data) ) - _writeSize = sizeof(request.data); - else - _writeSize = _writeFileSize - _writeOffset; - - request.hdr.size = _writeSize; + request.hdr.session = _downloadState.sessionId; + request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile; + request.hdr.offset = _downloadState.expectedOffset; + request.hdr.size = sizeof(request.data); - memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize); + if (firstRequest) { + _downloadState.retryCount = 0; + } else { + // Must used same sequence number as previous request + _expectedIncomingSeqNumber -= 2; + } _sendRequestExpectAck(&request); -#endif } -void FTPManager::_handleAck(MavlinkFTP::Request* ack) +void FTPManager::_burstReadFileBegin(void) { - - switch (ack->hdr.req_opcode) { - case MavlinkFTP::kCmdOpenFileRO: - _handlOpenFileROAck(ack); - break; - case MavlinkFTP::kCmdReadFile: - _handleReadFileAck(ack); - break; - case MavlinkFTP::kCmdBurstReadFile: - _handleBurstReadFileAck(ack); - break; - -#if 0 - case MavlinkFTP::kCmdListDirectory: - _listAckResponse(request); - break; - - case MavlinkFTP::kCmdOpenFileRO: - case MavlinkFTP::kCmdOpenFileWO: - _handlOpenFileROAck(request); - break; - - case MavlinkFTP::kCmdCreateFile: - _createAckResponse(request); - break; - - case MavlinkFTP::kCmdWriteFile: - _writeAckResponse(request); - break; -#endif - default: - // Ack back from operation which does not require additional work - _waitState = MavlinkFTP::kCmdNone; - break; - } + _burstReadFileWorker(true /* firstRequestr */); } -void FTPManager::_handleNak(MavlinkFTP::Request* nak) +void FTPManager::_burstReadFileAckOrNak(const MavlinkFTP::Request* ackOrNak) { - QString errorMsg; - MavlinkFTP::OpCode_t requestOpCode = static_cast(nak->hdr.req_opcode); - MavlinkFTP::ErrorCode_t errorCode = static_cast(nak->data[0]); - - if (errorCode == MavlinkFTP::kErrEOF) { - qCDebug(FTPManagerLog) << "_handleNak EOF"; - if (requestOpCode == MavlinkFTP::kCmdReadFile && _downloadState.bytesWritten == _downloadState.fileSize) { - // This could be an EOF on a normal read sequence, or an EOF for a read to fill in holes from a burst read. - // Either way it means we should be done. - _downloadComplete(QString()); - return; - } else if (requestOpCode == MavlinkFTP::kCmdBurstReadFile) { - // This is an EOF during a burst read, we still have to check for filling in missing data - if (_downloadState.missingData.count()) { - // We only call _requestMissingBurstData if there are no missing blocks since _requestMissingBurstData will start a new - // burst sequence if you call it with no missing blocks which would put us into an infinite loop on EOFs. - _requestMissingBurstData(); - return; - } else if (_downloadState.bytesWritten == _downloadState.fileSize) { - _downloadComplete(QString()); - return; - } - } - } - - // Nak's normally have 1 byte of data for error code, except for MavlinkFTP::kErrFailErrno which has additional byte for errno - if ((errorCode == MavlinkFTP::kErrFailErrno && nak->hdr.size != 2) || ((errorCode != MavlinkFTP::kErrFailErrno) && nak->hdr.size != 1)) { - errorMsg = tr("Invalid Nak format"); - } else if (errorCode == MavlinkFTP::kErrFailErrno) { - errorMsg = tr("errno %1").arg(nak->data[1]); - } else { - errorMsg = MavlinkFTP::errorCodeToString(errorCode); - } + MavlinkFTP::OpCode_t requestOpCode = static_cast(ackOrNak->hdr.req_opcode); - _waitState = MavlinkFTP::kCmdNone; - - switch (nak->hdr.req_opcode) { - case MavlinkFTP::kCmdOpenFileRO: - case MavlinkFTP::kCmdReadFile: - case MavlinkFTP::kCmdBurstReadFile: - _downloadComplete(tr("Download failed: %1").arg(errorMsg)); - break; - default: - // FIXME: Rest is NYI - break; - } -} - -void FTPManager::mavlinkMessageReceived(mavlink_message_t message) -{ - if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { + if (requestOpCode != MavlinkFTP::kCmdBurstReadFile) { + qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode); return; } - - mavlink_file_transfer_protocol_t data; - mavlink_msg_file_transfer_protocol_decode(&message, &data); - - // Make sure we are the target system - int qgcId = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(); - if (data.target_system != qgcId) { + if (ackOrNak->hdr.session != _downloadState.sessionId) { + qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId; return; } - - MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0]; - uint16_t incomingSeqNumber = request->hdr.seqNumber; - uint16_t expectedSeqNumber = _lastOutgoingRequest.hdr.seqNumber + 1; + _ackOrNakTimeoutTimer.stop(); - // ignore old/reordered packets (handle wrap-around properly) - if ((uint16_t)((expectedSeqNumber - 1) - incomingSeqNumber) < (std::numeric_limits::max()/2)) { - qCDebug(FTPManagerLog) << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber; - return; - } + if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) { + if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) { + qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber; + return; + } - _ackTimer.stop(); - - qCDebug(FTPManagerLog) << "mavlinkMessageReceived" << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast(request->hdr.req_opcode)); + qCDebug(FTPManagerLog) << QString("_burstReadFileAckOrNak: Ack offset(%1) size(%2) burstComplete(%3)").arg(ackOrNak->hdr.offset).arg(ackOrNak->hdr.size).arg(ackOrNak->hdr.burstComplete); + + if (ackOrNak->hdr.offset != _downloadState.expectedOffset) { + if (ackOrNak->hdr.offset > _downloadState.expectedOffset) { + // There is a hole in our data, record it as missing and continue on + MissingData_t missingData; + missingData.offset = _downloadState.expectedOffset; + missingData.cBytesMissing = ackOrNak->hdr.offset - _downloadState.expectedOffset; + _downloadState.rgMissingData.append(missingData); + qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: adding missing data offset:cBytesMissing" << missingData.offset << missingData.cBytesMissing; + } else { + // Offset is past what we have already seen, disregard and wait for something usefule + _ackOrNakTimeoutTimer.start(); + qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: received offset less than expected offset received:expected" << ackOrNak->hdr.offset << _downloadState.expectedOffset; + return; + } + } - if (incomingSeqNumber != expectedSeqNumber) { - switch (_waitState) { - case MavlinkFTP::kCmdOpenFileRO: - _downloadComplete(tr("Download failed: Unable to handle packet loss")); - break; - case MavlinkFTP::kCmdReadFile: - case MavlinkFTP::kCmdBurstReadFile: - // These can handle packet loss - break; -#if 0 - case kCOWrite: - _closeUploadSession(false /* failure */); - break; + _downloadState.file.seek(ackOrNak->hdr.offset); + int bytesWritten = _downloadState.file.write((const char*)ackOrNak->data, ackOrNak->hdr.size); + if (bytesWritten != ackOrNak->hdr.size) { + _downloadComplete(tr("Download failed: Error saving file")); + return; + } + _downloadState.bytesWritten += ackOrNak->hdr.size; + _downloadState.expectedOffset = ackOrNak->hdr.offset + ackOrNak->hdr.size; - case kCOOpenRead: - case kCOOpenBurst: - case kCOCreate: - // We could have an open session hanging around - _currentOperation = kCOIdle; - _sendResetCommand(); - break; -#endif - default: - // Don't need to do anything special - _waitState = MavlinkFTP::kCmdNone; - break; + if (_downloadState.fileSize != 0) { + emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize)); } - } - - // Move past the incoming sequence number for next request - _lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber; - if (request->hdr.opcode == MavlinkFTP::kRspAck) { - _handleAck(request); - } else if (request->hdr.opcode == MavlinkFTP::kRspNak) { - _handleNak(request); - } -} + if (ackOrNak->hdr.burstComplete) { + // The current burst is done, request next one in offset sequence + _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber; + _burstReadFileWorker(true /* firstRequest */); + } else { + // Still within a burst, next ack should come automatically + _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber + 1; + _ackOrNakTimeoutTimer.start(); + } + } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) { + if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) { + qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding Nak due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber; + return; + } -void FTPManager::listDirectory(const QString& dirPath) -{ - if (_waitState != MavlinkFTP::kCmdNone) { - _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete.")); - return; - } + MavlinkFTP::ErrorCode_t errorCode = static_cast(ackOrNak->data[0]); - _dedicatedLink = _vehicle->vehicleLinkManager()->primaryLink(); - if (!_dedicatedLink) { - _emitErrorMessage(tr("Command not sent. No Vehicle links.")); - return; + if (errorCode == MavlinkFTP::kErrEOF) { + // Burst sequence has gone through the whole file + qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak EOF"; + _advanceStateMachine(); + } else { + qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak); + _downloadComplete(tr("Download failed")); + } } - - // initialise the lister - _listPath = dirPath; - _listOffset = 0; - _waitState = MavlinkFTP::kCmdListDirectory; - - // and send the initial request - _sendListCommand(); } -void FTPManager::_fillRequestWithString(MavlinkFTP::Request* request, const QString& str) +void FTPManager::_burstReadFileTimeout(void) { - strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data)); - request->hdr.size = static_cast(strnlen((const char *)&request->data[0], sizeof(request->data))); + if (++_downloadState.retryCount > _maxRetry) { + qCDebug(FTPManagerLog) << QString("_burstReadFileTimeout retries exceeded"); + _downloadComplete(tr("Download failed")); + } else { + // Try again + qCDebug(FTPManagerLog) << QString("_burstReadFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset); + _burstReadFileWorker(false /* firstReqeust */); + } } -void FTPManager::_sendListCommand(void) +void FTPManager::_fillMissingBlocksWorker(bool firstRequest) { - MavlinkFTP::Request request; - - request.hdr.session = 0; - request.hdr.opcode = MavlinkFTP::kCmdListDirectory; - request.hdr.offset = _listOffset; - request.hdr.size = 0; - - _fillRequestWithString(&request, _listPath); - - qCDebug(FTPManagerLog) << "listDirectory: path:" << _listPath << "offset:" << _listOffset; - - _sendRequestExpectAck(&request); -} + if (_downloadState.rgMissingData.count()) { + MavlinkFTP::Request request; + MissingData_t& missingData = _downloadState.rgMissingData.first(); -bool FTPManager::download(const QString& from, const QString& toDir) -{ - qCDebug(FTPManagerLog) << "download from:" << from << "to:" << toDir; - return _downloadWorker(from, toDir); -} + uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytesMissing); -bool FTPManager::_downloadWorker(const QString& from, const QString& toDir) -{ - if (_waitState != MavlinkFTP::kCmdNone) { - qCDebug(FTPManagerLog) << "Cannot download. Already in another operation"; - return false; - } + qCDebug(FTPManagerLog) << "_fillMissingBlocksBegin: offset:cBytesToRead" << missingData.offset << cBytesToRead; - _dedicatedLink = _vehicle->vehicleLinkManager()->primaryLink(); - if (!_dedicatedLink) { - qCDebug(FTPManagerLog) << "Cannot download. Vehicle has no priority link"; - return false; - } + request.hdr.session = _downloadState.sessionId; + request.hdr.opcode = MavlinkFTP::kCmdReadFile; + request.hdr.offset = missingData.offset; + request.hdr.size = cBytesToRead; - _downloadState.reset(); - _downloadState.toDir.setPath(toDir); + if (firstRequest) { + _downloadState.retryCount = 0; + } else { + // Must used same sequence number as previous request + _expectedIncomingSeqNumber -= 2; + } + _downloadState.expectedOffset = request.hdr.offset; - QString strippedFrom; - QString ftpPrefix("mavlinkftp://"); - if (from.startsWith(ftpPrefix, Qt::CaseInsensitive)) { - strippedFrom = from.right(from.length() - ftpPrefix.length() + 1); + _sendRequestExpectAck(&request); } else { - strippedFrom = from; - } - - // We need to strip off the file name from the fully qualified path. We can't use the usual QDir - // routines because this path does not exist locally. - int lastDirSlashIndex; - for (lastDirSlashIndex=strippedFrom.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) { - if (strippedFrom[lastDirSlashIndex] == '/') { - break; + // We should have the full file now + if (_downloadState.bytesWritten == _downloadState.fileSize) { + _advanceStateMachine(); + } else { + qCDebug(FTPManagerLog) << "_fillMissingBlocksWorker: no missing blocks but file still incomplete - bytesWritten:fileSize" << _downloadState.bytesWritten << _downloadState.fileSize; + _downloadComplete(tr("Download failed")); } } - lastDirSlashIndex++; // move past slash - - _downloadState.fileName = strippedFrom.right(strippedFrom.size() - lastDirSlashIndex); - _waitState = MavlinkFTP::kCmdOpenFileRO; - - MavlinkFTP::Request request; - request.hdr.session = 0; - request.hdr.opcode = MavlinkFTP::kCmdOpenFileRO; - request.hdr.offset = 0; - request.hdr.size = 0; - _fillRequestWithString(&request, strippedFrom); - _sendRequestExpectAck(&request); +} - return true; +void FTPManager::_fillMissingBlocksBegin(void) +{ + _fillMissingBlocksWorker(true /* firstRequest */); } -/// @brief Uploads the specified file. -/// @param toPath File in UAS to upload to, fully qualified path -/// @param uploadFile Local file to upload from -void FTPManager::upload(const QString& /*toPath*/, const QFileInfo& /*uploadFile*/) +void FTPManager::_fillMissingBlocksAckOrNak(const MavlinkFTP::Request* ackOrNak) { -#if 0 - if(_currentOperation != kCOIdle){ - _emitErrorMessage(tr("UAS File manager busy. Try again later")); - return; - } + MavlinkFTP::OpCode_t requestOpCode = static_cast(ackOrNak->hdr.req_opcode); - _dedicatedLink = _vehicle->vehicleLinkManager()->primaryLink(); - if (!_dedicatedLink) { - _emitErrorMessage(tr("Command not sent. No Vehicle links.")); + if (requestOpCode != MavlinkFTP::kCmdReadFile) { + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode); return; } - - if (toPath.isEmpty()) { + if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) { + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber; return; } - - if (!uploadFile.isReadable()){ - _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path())); + if (ackOrNak->hdr.session != _downloadState.sessionId) { + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId; return; } - QFile file(uploadFile.absoluteFilePath()); - if (!file.open(QIODevice::ReadOnly)) { - _emitErrorMessage(tr("Unable to open local file for upload (%1)").arg(uploadFile.absoluteFilePath())); - return; - } + _ackOrNakTimeoutTimer.stop(); - _writeFileAccumulator = file.readAll(); - _writeFileSize = _writeFileAccumulator.size(); + if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) { + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Ack offset:size" << ackOrNak->hdr.offset << ackOrNak->hdr.size; - file.close(); + if (ackOrNak->hdr.offset != _downloadState.expectedOffset) { + if (++_downloadState.retryCount > _maxRetry) { + qCDebug(FTPManagerLog) << QString("_fillMissingBlocksAckOrNak: offset mismatch, retries exceeded"); + _downloadComplete(tr("Download failed")); + return; + } - if (_writeFileAccumulator.size() == 0) { - _emitErrorMessage(tr("Unable to read data from local file (%1)").arg(uploadFile.absoluteFilePath())); - return; - } + // Ask for current offset again + qCDebug(FTPManagerLog) << QString("_fillMissingBlocksAckOrNak: Ack offset mismatch retry, retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset); + _fillMissingBlocksWorker(false /* firstReqeust */); + return; + } - _currentOperation = kCOCreate; + _downloadState.file.seek(ackOrNak->hdr.offset); + int bytesWritten = _downloadState.file.write((const char*)ackOrNak->data, ackOrNak->hdr.size); + if (bytesWritten != ackOrNak->hdr.size) { + _downloadComplete(tr("Download failed: Error saving file")); + return; + } + _downloadState.bytesWritten += ackOrNak->hdr.size; + + MissingData_t& missingData = _downloadState.rgMissingData.first(); + missingData.offset += ackOrNak->hdr.size; + missingData.cBytesMissing -= ackOrNak->hdr.size; + if (missingData.cBytesMissing == 0) { + // This block is finished, remove it + _downloadState.rgMissingData.takeFirst(); + } - MavlinkFTP::Request request; - request.hdr.session = 0; - request.hdr.opcode = MavlinkFTP::kCmdCreateFile; - request.hdr.offset = 0; - request.hdr.size = 0; - _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName()); - _sendRequestExpectAck(&request); -#endif -} + if (_downloadState.fileSize != 0) { + emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize)); + } -void FTPManager::createDirectory(const QString& /*directory*/) -{ -#if 0 - if(_currentOperation != kCOIdle){ - _emitErrorMessage(tr("UAS File manager busy. Try again later")); - return; - } + // Move on to fill in possible next hole + _fillMissingBlocksWorker(true /* firstReqeust */); + } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) { + MavlinkFTP::ErrorCode_t errorCode = static_cast(ackOrNak->data[0]); - _currentOperation = kCOCreateDir; + if (errorCode == MavlinkFTP::kErrEOF) { + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak EOF"; + if (_downloadState.bytesWritten == _downloadState.fileSize) { + // We've successfully complete filling in all missing blocks + _advanceStateMachine(); + return; + } + } + + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak); + _downloadComplete(tr("Download failed")); + } - MavlinkFTP::Request request; - request.hdr.session = 0; - request.hdr.opcode = MavlinkFTP::kCmdCreateDirectory; - request.hdr.offset = 0; - request.hdr.size = 0; - _fillRequestWithString(&request, directory); - _sendRequestExpectAck(&request); -#endif } -/// @brief Sends a command which only requires an opcode and no additional data -/// @param opcode Opcode to send -/// @param newOpState State to put state machine into -/// @return TRUE: command sent, FALSE: command not sent, waiting for previous command to finish -bool FTPManager::_sendOpcodeOnlyCmd(MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpCode_t newWaitState) +void FTPManager::_fillMissingBlocksTimeout(void) { - if (_waitState != MavlinkFTP::kCmdNone) { - // Can't have multiple commands in play at the same time - return false; + if (++_downloadState.retryCount > _maxRetry) { + qCDebug(FTPManagerLog) << QString("_fillMissingBlocksTimeout retries exceeded"); + _downloadComplete(tr("Download failed")); + } else { + // Ask for current offset again + qCDebug(FTPManagerLog) << QString("_fillMissingBlocksTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset); + _fillMissingBlocksWorker(false /* firstReqeust */); } +} - _waitState = newWaitState; - +void FTPManager::_resetSessionsBegin(void) +{ MavlinkFTP::Request request; - request.hdr.session = 0; - request.hdr.opcode = opcode; - request.hdr.offset = 0; + request.hdr.opcode = MavlinkFTP::kCmdResetSessions; request.hdr.size = 0; _sendRequestExpectAck(&request); - - return true; } -void FTPManager::_ackTimeout(void) +void FTPManager::_resetSessionsAckOrNak(const MavlinkFTP::Request* ackOrNak) { - qCDebug(FTPManagerLog) << "_ackTimeout" << MavlinkFTP::opCodeToString(static_cast(_waitState)); - - switch (_waitState) { - case MavlinkFTP::kCmdReadFile: - // FIXME: retry count? - // Resend last request - _lastOutgoingRequest.hdr.seqNumber--; - _sendRequestExpectAck(&_lastOutgoingRequest); - return; - default: - break; - } + MavlinkFTP::OpCode_t requestOpCode = static_cast(ackOrNak->hdr.req_opcode); -#if 0 - if (++_ackNumTries <= _ackTimerMaxRetries) { - qCDebug(FTPManagerLog) << "ack timeout - retrying"; - if (_currentOperation == kCOBurst) { - // for burst downloads try to initiate a new burst - MavlinkFTP::Request request; - request.hdr.session = _activeSession; - request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile; - request.hdr.offset = _downloadOffset; - request.hdr.size = 0; - request.hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber; - - _sendRequestNoAck(&request); - } else { - _sendRequestNoAck(&_lastOutgoingRequest); - } + if (requestOpCode != MavlinkFTP::kCmdResetSessions) { + qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode); return; } -#endif - - // Make sure to set _currentOperation state before emitting error message. Code may respond - // to error message signal by sending another command, which will fail if state is not back - // to idle. FileView UI works this way with the List command. - - switch (_waitState) { - case MavlinkFTP::kCmdOpenFileRO: - case MavlinkFTP::kCmdBurstReadFile: - case MavlinkFTP::kCmdReadFile: - _downloadComplete(tr("Download failed: Vehicle did not respond to %1").arg(MavlinkFTP::opCodeToString(_waitState))); - break; -#if 0 - // FIXME: NYI - case kCOOpenRead: - case kCOOpenBurst: - _currentOperation = kCOIdle; - _emitErrorMessage(tr("Timeout waiting for ack: Download failed")); - _sendResetCommand(); - break; - - case kCOCreate: - _currentOperation = kCOIdle; - _emitErrorMessage(tr("Timeout waiting for ack: Upload failed")); - _sendResetCommand(); - break; - - case kCOWrite: - _closeUploadSession(false /* failure */); - _emitErrorMessage(tr("Timeout waiting for ack: Upload failed")); - break; -#endif - default: - { - MavlinkFTP::OpCode_t _lastCommand = _waitState; - _waitState = MavlinkFTP::kCmdNone; - _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(MavlinkFTP::opCodeToString(_lastCommand))); + if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) { + qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber; + return; } - break; + + _ackOrNakTimeoutTimer.stop(); + + if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) { + qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Ack"; + _advanceStateMachine(); + } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) { + qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak); + _downloadComplete(QString()); } } -void FTPManager::_sendResetCommand(void) +void FTPManager::_resetSessionsTimeout(void) { - MavlinkFTP::Request request; - request.hdr.opcode = MavlinkFTP::kCmdResetSessions; - request.hdr.size = 0; - _waitState = MavlinkFTP::kCmdResetSessions; - _sendRequestExpectAck(&request); + qCDebug(FTPManagerLog) << "_resetSessionsTimeout"; + _downloadComplete(QString()); } void FTPManager::_emitErrorMessage(const QString& msg) @@ -822,41 +525,29 @@ void FTPManager::_emitErrorMessage(const QString& msg) emit commandError(msg); } -void FTPManager::_emitListEntry(const QString& entry) -{ - qCDebug(FTPManagerLog) << "_emitListEntry" << entry; - emit listEntry(entry); -} - void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request) { - _ackTimer.start(); - - request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber; - qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber; + LinkInterface* primaryLink = _vehicle->vehicleLinkManager()->primaryLink(); - if (request->hdr.size <= sizeof(request->data)) { - memcpy(&_lastOutgoingRequest, request, sizeof(MavlinkFTP::RequestHeader) + request->hdr.size); + _ackOrNakTimeoutTimer.start(); + + if (primaryLink) { + request->hdr.seqNumber = _expectedIncomingSeqNumber + 1; // Outgoing is 1 past last incoming + _expectedIncomingSeqNumber += 2; + + qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber; + + mavlink_message_t message; + mavlink_msg_file_transfer_protocol_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), + qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + primaryLink->mavlinkChannel(), + &message, + 0, // Target network, 0=broadcast? + _vehicle->id(), + MAV_COMP_ID_AUTOPILOT1, + (uint8_t*)request); // Payload + _vehicle->sendMessageOnLinkThreadSafe(primaryLink, message); } else { - // FIXME: Shouldn't this fail something? - qCCritical(FTPManagerLog) << "request length too long:" << request->hdr.size; + qCDebug(FTPManagerLog) << "_sendRequestExpectAck No primary link. Allowing timeout to fail sequence."; } - - _sendRequestNoAck(request); -} - -void FTPManager::_sendRequestNoAck(MavlinkFTP::Request* request) -{ - qCDebug(FTPManagerLog) << "_sendRequestNoAck opcode:" << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)); - - mavlink_message_t message; - mavlink_msg_file_transfer_protocol_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), - _dedicatedLink->mavlinkChannel(), - &message, - 0, // Target network, 0=broadcast? - _vehicle->id(), - MAV_COMP_ID_AUTOPILOT1, - (uint8_t*)request); // Payload - _vehicle->sendMessageOnLinkThreadSafe(_dedicatedLink, message); } diff --git a/src/Vehicle/FTPManager.h b/src/Vehicle/FTPManager.h index 021641bd6..fb000393f 100644 --- a/src/Vehicle/FTPManager.h +++ b/src/Vehicle/FTPManager.h @@ -7,7 +7,6 @@ * ****************************************************************************/ - #pragma once #include @@ -26,6 +25,8 @@ class Vehicle; class FTPManager : public QObject { Q_OBJECT + + friend class Vehicle; public: FTPManager(Vehicle* vehicle); @@ -36,32 +37,9 @@ public: /// @return true: download has started, false: error, no download /// Signals downloadComplete, commandError, commandProgress bool download(const QString& from, const QString& toDir); - - /// Stream downloads the specified file. - /// @param from File to download from UAS, fully qualified path. May be in the format mavlinkftp://... - /// @param toDir Local directory to download file to - /// @return true: download has started, false: error, no download - /// Signals downloadComplete, commandError, commandProgress - bool burstDownload(const QString& from, const QString& toDir); - - /// Lists the specified directory. Emits listEntry signal for each entry, followed by listComplete signal. - /// @param dirPath Fully qualified path to list - void listDirectory(const QString& dirPath); - - /// Upload the specified file to the specified location - void upload(const QString& toPath, const QFileInfo& uploadFile); - - /// Create a remote directory - void createDirectory(const QString& directory); - - void mavlinkMessageReceived(mavlink_message_t message); signals: - void downloadComplete (const QString& file, const QString& errorMsg); - void uploadComplete (const QString& errorMsg); - - /// Signalled to indicate a new directory entry was received. - void listEntry(const QString& entry); + void downloadComplete(const QString& file, const QString& errorMsg); // Signals associated with all commands @@ -75,58 +53,30 @@ signals: void commandProgress(int value); private slots: - void _ackTimeout(void); + void _ackOrNakTimeout(void); private: - bool _sendOpcodeOnlyCmd (MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpCode_t newWaitState); - void _emitErrorMessage (const QString& msg); - void _emitListEntry (const QString& entry); - void _sendRequestExpectAck (MavlinkFTP::Request* request); - void _sendRequestNoAck (MavlinkFTP::Request* request); - void _sendMessageOnLink (LinkInterface* link, mavlink_message_t message); - void _fillRequestWithString (MavlinkFTP::Request* request, const QString& str); - void _handlOpenFileROAck (MavlinkFTP::Request* ack); - void _handleReadFileAck (MavlinkFTP::Request* ack); - void _handleBurstReadFileAck (MavlinkFTP::Request* ack); - void _listAckResponse (MavlinkFTP::Request* listAck); - void _createAckResponse (MavlinkFTP::Request* createAck); - void _writeAckResponse (MavlinkFTP::Request* writeAck); - void _writeFileDatablock (void); - void _sendListCommand (void); - void _sendResetCommand (void); - void _downloadComplete (const QString& errorMsg); - void _uploadComplete (const QString& errorMsg); - bool _downloadWorker (const QString& from, const QString& toDir); - void _requestMissingBurstData(void); - void _handleAck (MavlinkFTP::Request* ack); - void _handleNak (MavlinkFTP::Request* nak); - - MavlinkFTP::OpCode_t _waitState = MavlinkFTP::kCmdNone; ///< Current operation of state machine - QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack - int _ackNumTries; ///< current number of tries - Vehicle* _vehicle; - LinkInterface* _dedicatedLink = nullptr; ///< Link to use for communication - MavlinkFTP::Request _lastOutgoingRequest; ///< contains the last outgoing packet - unsigned _listOffset; ///< offset for the current List operation - QString _listPath; ///< path for the current List operation - uint8_t _activeSession = 0; ///< currently active session, 0 for none - uint32_t _readOffset; ///< current read offset - - uint32_t _writeOffset; ///< current write offset - uint32_t _writeSize; ///< current write data size - uint32_t _writeFileSize; ///< Size of file being uploaded - QByteArray _writeFileAccumulator; ///< Holds file being uploaded - + typedef void (FTPManager::*StateBeginFn) (void); + typedef void (FTPManager::*StateAckNakFn) (const MavlinkFTP::Request* ackOrNak); + typedef void (FTPManager::*StateTimeoutFn) (void); + + typedef struct { + StateBeginFn beginFn; + StateAckNakFn ackNakFn; + StateTimeoutFn timeoutFn; + } StateFunctions_t; + typedef struct { uint32_t offset; - uint32_t cBytes; + uint32_t cBytesMissing; } MissingData_t; - struct { - uint32_t expectedBurstOffset; ///< offset which should be coming next in a burst sequence - uint32_t expectedReadOffset; ///< offset which should be coming from a hole filling read request + typedef struct { + uint8_t sessionId; + uint32_t expectedOffset; ///< offset which should be coming next uint32_t bytesWritten; - QList missingData; + QList rgMissingData; + QString fullPathOnVehicle; ///< Fully qualified path to file on vehicle QDir toDir; ///< Directory to download file to QString fileName; ///< Filename (no path) for download file uint32_t fileSize; ///< Size of file being downloaded @@ -134,17 +84,51 @@ private: int retryCount; void reset() { - expectedBurstOffset = 0; - expectedReadOffset = 0; - bytesWritten = 0; - retryCount = 0; - missingData.clear(); + sessionId = 0; + expectedOffset = 0; + bytesWritten = 0; + retryCount = 0; + fileSize = 0; + fullPathOnVehicle.clear(); + fileName.clear(); + rgMissingData.clear(); file.close(); } - } _downloadState; + } DownloadState_t; + + + void _mavlinkMessageReceived (const mavlink_message_t& message); + void _startStateMachine (void); + void _advanceStateMachine (void); + void _openFileROBegin (void); + void _openFileROAckOrNak (const MavlinkFTP::Request* ackOrNak); + void _openFileROTimeout (void); + void _burstReadFileBegin (void); + void _burstReadFileAckOrNak (const MavlinkFTP::Request* ackOrNak); + void _burstReadFileTimeout (void); + void _fillMissingBlocksBegin (void); + void _fillMissingBlocksAckOrNak (const MavlinkFTP::Request* ackOrNak); + void _fillMissingBlocksTimeout (void); + void _resetSessionsBegin (void); + void _resetSessionsAckOrNak (const MavlinkFTP::Request* ackOrNak); + void _resetSessionsTimeout (void); + QString _errorMsgFromNak (const MavlinkFTP::Request* nak); + void _sendRequestExpectAck (MavlinkFTP::Request* request); + void _downloadCompleteNoError (void) { _downloadComplete(QString()); } + void _downloadComplete (const QString& errorMsg); + void _emitErrorMessage (const QString& msg); + void _fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str); + void _fillMissingBlocksWorker (bool firstRequest); + void _burstReadFileWorker (bool firstRequest); - static const int _ackTimerTimeoutMsecs = 1000; - static const int _ackTimerMaxRetries = 6; - static const int _maxRetry = 5; + Vehicle* _vehicle; + QList _rgStateMachine; + DownloadState_t _downloadState; + QTimer _ackOrNakTimeoutTimer; + int _currentStateMachineIndex = -1; + uint16_t _expectedIncomingSeqNumber = 0; + + static const int _ackOrNakTimeoutMsecs = 1000; + static const int _maxRetry = 3; }; diff --git a/src/Vehicle/FTPManagerTest.cc b/src/Vehicle/FTPManagerTest.cc index 1610ab983..f5346cb58 100644 --- a/src/Vehicle/FTPManagerTest.cc +++ b/src/Vehicle/FTPManagerTest.cc @@ -17,6 +17,11 @@ const FTPManagerTest::TestCase_t FTPManagerTest::_rgTestCases[] = { { "/version.json" }, }; +void FTPManagerTest::cleanup(void) +{ + _disconnectMockLink(); +} + void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase) { _connectMockLinkNoInitialConnectSequence(); diff --git a/src/Vehicle/FTPManagerTest.h b/src/Vehicle/FTPManagerTest.h index 1ecb3e9b4..0ab2b8d7a 100644 --- a/src/Vehicle/FTPManagerTest.h +++ b/src/Vehicle/FTPManagerTest.h @@ -20,6 +20,9 @@ private slots: void _performTestCases (void); void _testLostPackets (void); + // Overrides from UnitTest + void cleanup(void) override; + private: typedef struct { const char* file; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index cd7089de7..b5119d33a 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -600,7 +600,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes if (!_terrainProtocolHandler->mavlinkMessageReceived(message)) { return; } - _ftpManager->mavlinkMessageReceived(message); + _ftpManager->_mavlinkMessageReceived(message); _parameterManager->mavlinkMessageReceived(message); _waitForMavlinkMessageMessageReceived(message); diff --git a/src/comm/MockLink.Parameter.MetaData.json b/src/comm/MockLink.Parameter.MetaData.json index 69fe58f1a..f024796ec 100644 --- a/src/comm/MockLink.Parameter.MetaData.json +++ b/src/comm/MockLink.Parameter.MetaData.json @@ -13,8 +13,8 @@ "units": "SD", "default": 1, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 5 + "min": 1, + "max": 5 }, { "name": "ASPD_BETA_NOISE", @@ -26,8 +26,8 @@ "units": "rad", "default": 0.3, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "ASPD_DO_CHECKS", @@ -39,8 +39,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ASPD_FALLBACK", @@ -62,8 +62,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ASPD_FS_INNOV", @@ -74,8 +74,8 @@ "longDesc": "This specifies the minimum airspeed test ratio required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Start with a value of 1.0 when tuning. When tas_test_ratio is > 1.0 it indicates the inconsistency between predicted and measured airspeed is large enough to cause the navigation EKF to reject airspeed measurements. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "default": 1, "decimalPlaces": 3, - "minValue": 0.5, - "maxValue": 3 + "min": 0.5, + "max": 3 }, { "name": "ASPD_FS_INTEG", @@ -87,8 +87,8 @@ "units": "s", "default": -1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 30 + "min": -3.40282e+38, + "max": 30 }, { "name": "ASPD_FS_T1", @@ -100,8 +100,8 @@ "units": "s", "default": 3, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "ASPD_FS_T2", @@ -113,8 +113,8 @@ "units": "s", "default": 100, "decimalPlaces": 3, - "minValue": 10, - "maxValue": 1000 + "min": 10, + "max": 1000 }, { "name": "ASPD_PRIMARY", @@ -147,8 +147,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ASPD_SCALE", @@ -159,8 +159,8 @@ "longDesc": "Scale can either be entered manually, or estimated in-flight by setting ASPD_SCALE_EST to 1.", "default": 1, "decimalPlaces": 3, - "minValue": 0.5, - "maxValue": 1.5 + "min": 0.5, + "max": 1.5 }, { "name": "ASPD_SCALE_EST", @@ -171,8 +171,8 @@ "longDesc": "Turns the automatic airspeed scale (scale from IAS to CAS/EAS) on or off. It is recommended to fly level altitude while performing the estimation. Set to 1 to start estimation (best when already flying). Set to 0 to end scale estimation. The estimated scale is then saved using the ASPD_SCALE parameter.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ASPD_SC_P_NOISE", @@ -184,8 +184,8 @@ "units": "1/s", "default": 0.0001, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 0.1 + "min": 0, + "max": 0.1 }, { "name": "ASPD_STALL", @@ -197,8 +197,8 @@ "units": "m/s", "default": 10, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "ASPD_TAS_GATE", @@ -210,8 +210,8 @@ "units": "SD", "default": 3, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 5 + "min": 1, + "max": 5 }, { "name": "ASPD_TAS_NOISE", @@ -223,8 +223,8 @@ "units": "m/s", "default": 1.4, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 4 + "min": 0, + "max": 4 }, { "name": "ASPD_W_P_NOISE", @@ -236,8 +236,8 @@ "units": "m/s/s", "default": 0.1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "ATT_ACC_COMP", @@ -247,8 +247,8 @@ "shortDesc": "Acceleration compensation based on GPS velocity", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ATT_BIAS_MAX", @@ -259,8 +259,8 @@ "units": "rad/s", "default": 0.05, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "ATT_EXT_HDG_M", @@ -284,8 +284,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "ATT_MAG_DECL", @@ -297,8 +297,8 @@ "units": "deg", "default": 0, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "ATT_MAG_DECL_A", @@ -308,8 +308,8 @@ "shortDesc": "Automatic GPS based declination compensation", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ATT_W_ACC", @@ -319,8 +319,8 @@ "shortDesc": "Complimentary filter accelerometer weight", "default": 0.2, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "ATT_W_EXT_HDG", @@ -330,8 +330,8 @@ "shortDesc": "Complimentary filter external heading weight", "default": 0.1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "ATT_W_GYRO_BIAS", @@ -341,8 +341,8 @@ "shortDesc": "Complimentary filter gyroscope bias weight", "default": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "ATT_W_MAG", @@ -353,8 +353,8 @@ "longDesc": "Set to 0 to avoid using the magnetometer.", "default": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "BAT{n}_A_PER_V", @@ -366,8 +366,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 8, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT{n}_CAPACITY", @@ -381,8 +381,8 @@ "increment": 50, "rebootRequired": true, "decimalPlaces": 0, - "minValue": -1, - "maxValue": 100000 + "min": -1, + "max": 100000 }, { "name": "BAT{n}_I_CHANNEL", @@ -394,8 +394,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "BAT{n}_N_CELLS", @@ -469,8 +469,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "BAT{n}_R_INTERNAL", @@ -484,8 +484,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": -1, - "maxValue": 0.2 + "min": -1, + "max": 0.2 }, { "name": "BAT{n}_SOURCE", @@ -511,8 +511,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "BAT{n}_V_CHANNEL", @@ -524,8 +524,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "BAT{n}_V_CHARGED", @@ -539,8 +539,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT{n}_V_DIV", @@ -552,8 +552,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 8, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT{n}_V_EMPTY", @@ -567,8 +567,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT{n}_V_LOAD_DROP", @@ -582,8 +582,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0.07, - "maxValue": 0.5 + "min": 0.07, + "max": 0.5 }, { "name": "BAT_ADC_CHANNEL", @@ -593,8 +593,8 @@ "shortDesc": "This parameter is deprecated. Please use BAT1_ADC_CHANNEL", "default": -1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "BAT_A_PER_V", @@ -604,8 +604,8 @@ "shortDesc": "This parameter is deprecated. Please use BAT1_A_PER_V", "default": -1, "decimalPlaces": 8, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT_CAPACITY", @@ -619,8 +619,8 @@ "increment": 50, "rebootRequired": true, "decimalPlaces": 0, - "minValue": -1, - "maxValue": 100000 + "min": -1, + "max": 100000 }, { "name": "BAT_CRIT_THR", @@ -634,8 +634,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0.05, - "maxValue": 0.25 + "min": 0.05, + "max": 0.25 }, { "name": "BAT_C_MULT", @@ -646,8 +646,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 1, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT_EMERGEN_THR", @@ -661,8 +661,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0.03, - "maxValue": 0.1 + "min": 0.03, + "max": 0.1 }, { "name": "BAT_LOW_THR", @@ -676,8 +676,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0.12, - "maxValue": 0.5 + "min": 0.12, + "max": 0.5 }, { "name": "BAT_N_CELLS", @@ -756,8 +756,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "BAT_R_INTERNAL", @@ -770,8 +770,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 0.2 + "min": -1, + "max": 0.2 }, { "name": "BAT_SOURCE", @@ -792,8 +792,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "BAT_V_CHARGED", @@ -807,8 +807,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT_V_DIV", @@ -818,8 +818,8 @@ "shortDesc": "This parameter is deprecated. Please use BAT1_V_DIV", "default": -1, "decimalPlaces": 8, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT_V_EMPTY", @@ -833,8 +833,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "BAT_V_LOAD_DROP", @@ -848,8 +848,8 @@ "increment": 0.01, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0.07, - "maxValue": 0.5 + "min": 0.07, + "max": 0.5 }, { "name": "BAT_V_OFFS_CURR", @@ -860,8 +860,8 @@ "longDesc": "This offset will be subtracted before calculating the battery current based on the voltage.", "default": 0, "decimalPlaces": 8, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC{n}_EN", @@ -871,8 +871,8 @@ "shortDesc": "Accelerometer /1 enabled", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_ACC{n}_ID", @@ -882,8 +882,8 @@ "shortDesc": "ID of the Accelerometer that the calibration is for", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_ACC{n}_XOFF", @@ -893,8 +893,8 @@ "shortDesc": "Accelerometer X-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC{n}_XSCALE", @@ -904,8 +904,8 @@ "shortDesc": "Accelerometer X-axis scaling factor", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC{n}_YOFF", @@ -915,8 +915,8 @@ "shortDesc": "Accelerometer Y-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC{n}_YSCALE", @@ -926,8 +926,8 @@ "shortDesc": "Accelerometer Y-axis scaling factor", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC{n}_ZOFF", @@ -937,8 +937,8 @@ "shortDesc": "Accelerometer Z-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC{n}_ZSCALE", @@ -948,8 +948,8 @@ "shortDesc": "Accelerometer Z-axis scaling factor", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_ACC_PRIME", @@ -959,8 +959,8 @@ "shortDesc": "Primary accel ID", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_AIR_CMODEL", @@ -985,8 +985,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_AIR_TUBED_MM", @@ -997,8 +997,8 @@ "units": "millimeter", "default": 1.5, "decimalPlaces": 3, - "minValue": 0.1, - "maxValue": 100 + "min": 0.1, + "max": 100 }, { "name": "CAL_AIR_TUBELEN", @@ -1010,8 +1010,8 @@ "units": "meter", "default": 0.2, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 2 + "min": 0.01, + "max": 2 }, { "name": "CAL_GYRO{n}_EN", @@ -1021,8 +1021,8 @@ "shortDesc": "Gyro 0 enabled", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_GYRO{n}_ID", @@ -1032,8 +1032,8 @@ "shortDesc": "ID of the Gyro that the calibration is for", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_GYRO{n}_XOFF", @@ -1043,8 +1043,8 @@ "shortDesc": "Gyro X-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_GYRO{n}_YOFF", @@ -1054,8 +1054,8 @@ "shortDesc": "Gyro Y-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_GYRO{n}_ZOFF", @@ -1065,8 +1065,8 @@ "shortDesc": "Gyro Z-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_GYRO_PRIME", @@ -1076,8 +1076,8 @@ "shortDesc": "Primary gyro ID", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_MAG{n}_EN", @@ -1087,8 +1087,8 @@ "shortDesc": "Mag 0 enabled", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_MAG{n}_ID", @@ -1098,8 +1098,8 @@ "shortDesc": "ID of Magnetometer the calibration is for", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_MAG{n}_ROT", @@ -1221,8 +1221,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 30 + "min": -1, + "max": 30 }, { "name": "CAL_MAG{n}_XCOMP", @@ -1232,8 +1232,8 @@ "shortDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_XOFF", @@ -1243,8 +1243,8 @@ "shortDesc": "Magnetometer X-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_XSCALE", @@ -1254,8 +1254,8 @@ "shortDesc": "Magnetometer X-axis scaling factor", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_YCOMP", @@ -1265,8 +1265,8 @@ "shortDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_YOFF", @@ -1276,8 +1276,8 @@ "shortDesc": "Magnetometer Y-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_YSCALE", @@ -1287,8 +1287,8 @@ "shortDesc": "Magnetometer Y-axis scaling factor", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_ZCOMP", @@ -1298,8 +1298,8 @@ "shortDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_ZOFF", @@ -1309,8 +1309,8 @@ "shortDesc": "Magnetometer Z-axis offset", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG{n}_ZSCALE", @@ -1320,8 +1320,8 @@ "shortDesc": "Magnetometer Z-axis scaling factor", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CAL_MAG_COMP_TYP", @@ -1349,8 +1349,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_MAG_PRIME", @@ -1360,8 +1360,8 @@ "shortDesc": "Primary mag ID", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAL_MAG_SIDES", @@ -1386,8 +1386,8 @@ } ], "decimalPlaces": 3, - "minValue": 34, - "maxValue": 63 + "min": 34, + "max": 63 }, { "name": "CAM_CAP_DELAY", @@ -1399,8 +1399,8 @@ "units": "ms", "default": 0, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "CAM_CAP_EDGE", @@ -1421,8 +1421,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAM_CAP_FBACK", @@ -1434,8 +1434,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CAM_CAP_MODE", @@ -1461,8 +1461,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "CANNODE_BITRATE", @@ -1472,8 +1472,8 @@ "shortDesc": "UAVCAN CAN bus bitrate", "default": 1e+06, "decimalPlaces": 3, - "minValue": 20000, - "maxValue": 1e+06 + "min": 20000, + "max": 1e+06 }, { "name": "CANNODE_NODE_ID", @@ -1484,8 +1484,8 @@ "longDesc": "Read the specs at http://uavcan.org to learn more about Node ID.", "default": 120, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 125 + "min": 1, + "max": 125 }, { "name": "CBRK_AIRSPD_CHK", @@ -1497,8 +1497,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 162128 + "min": 0, + "max": 162128 }, { "name": "CBRK_BUZZER", @@ -1510,8 +1510,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 782097 + "min": 0, + "max": 782097 }, { "name": "CBRK_ENGINEFAIL", @@ -1523,8 +1523,8 @@ "default": 284953, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 284953 + "min": 0, + "max": 284953 }, { "name": "CBRK_FLIGHTTERM", @@ -1536,8 +1536,8 @@ "default": 121212, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 121212 + "min": 0, + "max": 121212 }, { "name": "CBRK_IO_SAFETY", @@ -1549,8 +1549,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 22027 + "min": 0, + "max": 22027 }, { "name": "CBRK_RATE_CTRL", @@ -1562,8 +1562,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 140253 + "min": 0, + "max": 140253 }, { "name": "CBRK_SUPPLY_CHK", @@ -1575,8 +1575,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 894281 + "min": 0, + "max": 894281 }, { "name": "CBRK_USB_CHK", @@ -1588,8 +1588,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 197848 + "min": 0, + "max": 197848 }, { "name": "CBRK_VELPOSERR", @@ -1601,8 +1601,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 201607 + "min": 0, + "max": 201607 }, { "name": "CBRK_VTOLARMING", @@ -1614,8 +1614,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 159753 + "min": 0, + "max": 159753 }, { "name": "COM_ARM_AUTH", @@ -1626,8 +1626,8 @@ "longDesc": "Default value: (10 << 0 | 1000 << 8 | 0 << 24) = 256010 - authorizer system id = 10 - authentication method parameter = 10000msec of timeout - authentication method = during arm", "default": 256010, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_ARM_AUTH_REQ", @@ -1638,8 +1638,8 @@ "longDesc": "The default allows to arm the vehicle without a arm authorization.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_ARM_CHK_ESCS", @@ -1650,8 +1650,8 @@ "longDesc": "This param is specific for ESCs reporting status. Normal ESCs configurations are not affected by the change of this param.", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_ARM_EKF_AB", @@ -1663,8 +1663,8 @@ "default": 0.0022, "increment": 0.0001, "decimalPlaces": 4, - "minValue": 0.001, - "maxValue": 0.01 + "min": 0.001, + "max": 0.01 }, { "name": "COM_ARM_EKF_GB", @@ -1676,8 +1676,8 @@ "default": 0.0011, "increment": 0.0001, "decimalPlaces": 4, - "minValue": 0.0001, - "maxValue": 0.0017 + "min": 0.0001, + "max": 0.0017 }, { "name": "COM_ARM_EKF_HGT", @@ -1688,8 +1688,8 @@ "default": 1, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "COM_ARM_EKF_POS", @@ -1700,8 +1700,8 @@ "default": 0.5, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "COM_ARM_EKF_VEL", @@ -1712,8 +1712,8 @@ "default": 0.5, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "COM_ARM_EKF_YAW", @@ -1724,8 +1724,8 @@ "default": 0.5, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "COM_ARM_IMU_ACC", @@ -1737,8 +1737,8 @@ "default": 0.7, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "COM_ARM_IMU_GYR", @@ -1750,8 +1750,8 @@ "default": 0.25, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0.02, - "maxValue": 0.3 + "min": 0.02, + "max": 0.3 }, { "name": "COM_ARM_MAG_ANG", @@ -1762,8 +1762,8 @@ "units": "deg", "default": 30, "decimalPlaces": 3, - "minValue": 3, - "maxValue": 180 + "min": 3, + "max": 180 }, { "name": "COM_ARM_MAG_STR", @@ -1774,8 +1774,8 @@ "longDesc": "Deny arming if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK)", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_ARM_MIS_REQ", @@ -1786,8 +1786,8 @@ "longDesc": "The default allows to arm the vehicle without a valid mission.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_ARM_SWISBTN", @@ -1798,8 +1798,8 @@ "longDesc": "The default uses the arm switch as real switch. If parameter set button gets handled like stick arming.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_ARM_WO_GPS", @@ -1810,8 +1810,8 @@ "longDesc": "The default allows to arm the vehicle without GPS signal.", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_CPU_MAX", @@ -1824,8 +1824,8 @@ "default": 90, "increment": 1, "decimalPlaces": 0, - "minValue": -1, - "maxValue": 100 + "min": -1, + "max": 100 }, { "name": "COM_DISARM_LAND", @@ -1837,8 +1837,8 @@ "units": "s", "default": 2, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "COM_DISARM_PRFLT", @@ -1850,8 +1850,8 @@ "units": "s", "default": 10, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "COM_DL_LOSS_T", @@ -1864,8 +1864,8 @@ "default": 10, "increment": 1, "decimalPlaces": 1, - "minValue": 5, - "maxValue": 300 + "min": 5, + "max": 300 }, { "name": "COM_EF_C2T", @@ -1878,8 +1878,8 @@ "default": 5, "increment": 1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 50 + "min": 0, + "max": 50 }, { "name": "COM_EF_THROT", @@ -1892,8 +1892,8 @@ "default": 0.5, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "COM_EF_TIME", @@ -1906,8 +1906,8 @@ "default": 10, "increment": 1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 60 + "min": 0, + "max": 60 }, { "name": "COM_FLIGHT_UUID", @@ -1919,8 +1919,8 @@ "default": 0, "volatile": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2.14748e+09 + "min": 0, + "max": 2.14748e+09 }, { "name": "COM_FLTMODE1", @@ -1989,8 +1989,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_FLTMODE2", @@ -2059,8 +2059,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_FLTMODE3", @@ -2129,8 +2129,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_FLTMODE4", @@ -2199,8 +2199,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_FLTMODE5", @@ -2269,8 +2269,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_FLTMODE6", @@ -2339,8 +2339,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_FLT_PROFILE", @@ -2369,8 +2369,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_HLDL_LOSS_T", @@ -2382,8 +2382,8 @@ "units": "s", "default": 120, "decimalPlaces": 3, - "minValue": 60, - "maxValue": 3600 + "min": 60, + "max": 3600 }, { "name": "COM_HLDL_REG_T", @@ -2395,8 +2395,8 @@ "units": "s", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 60 + "min": 0, + "max": 60 }, { "name": "COM_HOME_H_T", @@ -2409,8 +2409,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 2, - "minValue": 2, - "maxValue": 15 + "min": 2, + "max": 15 }, { "name": "COM_HOME_V_T", @@ -2423,8 +2423,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 2, - "minValue": 5, - "maxValue": 25 + "min": 5, + "max": 25 }, { "name": "COM_KILL_DISARM", @@ -2436,8 +2436,8 @@ "default": 5, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 30 + "min": 0, + "max": 30 }, { "name": "COM_LKDOWN_TKO", @@ -2449,8 +2449,8 @@ "units": "s", "default": 3, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 5 + "min": -1, + "max": 5 }, { "name": "COM_LOW_BAT_ACT", @@ -2476,8 +2476,8 @@ } ], "decimalPlaces": 0, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_MOT_TEST_EN", @@ -2488,8 +2488,8 @@ "longDesc": "If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that allows spinning the motors for testing purposes.", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_OBL_ACT", @@ -2526,8 +2526,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_OBL_RC_ACT", @@ -2576,8 +2576,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_OBS_AVOID", @@ -2587,8 +2587,8 @@ "shortDesc": "Flag to enable obstacle avoidance", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_OF_LOSS_T", @@ -2600,8 +2600,8 @@ "default": 0.5, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 60 + "min": 0, + "max": 60 }, { "name": "COM_POSCTL_NAVL", @@ -2622,8 +2622,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_POS_FS_DELAY", @@ -2636,8 +2636,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 100 + "min": 1, + "max": 100 }, { "name": "COM_POS_FS_EPH", @@ -2649,8 +2649,8 @@ "units": "m", "default": 5, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "COM_POS_FS_EPV", @@ -2662,8 +2662,8 @@ "units": "m", "default": 10, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "COM_POS_FS_GAIN", @@ -2675,8 +2675,8 @@ "default": 10, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_POS_FS_PROB", @@ -2689,8 +2689,8 @@ "default": 30, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 100 + "min": 1, + "max": 100 }, { "name": "COM_POWER_COUNT", @@ -2701,8 +2701,8 @@ "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.", "default": 1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 4 + "min": 0, + "max": 4 }, { "name": "COM_PREARM_MODE", @@ -2727,8 +2727,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_RC_ARM_HYST", @@ -2739,8 +2739,8 @@ "longDesc": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "default": 1000, "decimalPlaces": 3, - "minValue": 100, - "maxValue": 1500 + "min": 100, + "max": 1500 }, { "name": "COM_RC_IN_MODE", @@ -2765,8 +2765,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "COM_RC_LOSS_T", @@ -2779,8 +2779,8 @@ "default": 0.5, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 35 + "min": 0, + "max": 35 }, { "name": "COM_RC_OVERRIDE", @@ -2791,8 +2791,8 @@ "longDesc": "When RC stick override is enabled, moving the RC sticks immediately gives control back to the pilot (switches to manual position mode): bit 0: Enable for auto modes (except for in critical battery reaction), bit 1: Enable for offboard mode. Only has an effect on multicopters, and VTOLS in multicopter mode.", "default": 1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3 + "min": 0, + "max": 3 }, { "name": "COM_RC_STICK_OV", @@ -2805,8 +2805,8 @@ "default": 12, "increment": 0.05, "decimalPlaces": 0, - "minValue": 5, - "maxValue": 40 + "min": 5, + "max": 40 }, { "name": "COM_TAKEOFF_ACT", @@ -2827,8 +2827,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "COM_VEL_FS_EVH", @@ -2840,8 +2840,8 @@ "units": "m/s", "default": 1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CP_DELAY", @@ -2853,8 +2853,8 @@ "units": "seconds", "default": 0.4, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "CP_DIST", @@ -2866,8 +2866,8 @@ "units": "meters", "default": -1, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 15 + "min": -1, + "max": 15 }, { "name": "CP_GO_NO_DATA", @@ -2878,8 +2878,8 @@ "longDesc": "Only used in Position mode.", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "CP_GUIDE_ANG", @@ -2891,8 +2891,8 @@ "units": "[deg]", "default": 30, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "DSHOT_CONFIG", @@ -2926,8 +2926,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "DSHOT_MIN", @@ -2940,8 +2940,8 @@ "default": 0.055, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "DSHOT_TEL_CFG", @@ -2995,8 +2995,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_ABIAS_INIT", @@ -3008,8 +3008,8 @@ "default": 0.2, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.5 + "min": 0, + "max": 0.5 }, { "name": "EKF2_ABL_ACCLIM", @@ -3020,8 +3020,8 @@ "units": "m/s/s", "default": 25, "decimalPlaces": 1, - "minValue": 20, - "maxValue": 200 + "min": 20, + "max": 200 }, { "name": "EKF2_ABL_GYRLIM", @@ -3032,8 +3032,8 @@ "units": "rad/s", "default": 3, "decimalPlaces": 1, - "minValue": 2, - "maxValue": 20 + "min": 2, + "max": 20 }, { "name": "EKF2_ABL_LIM", @@ -3044,8 +3044,8 @@ "units": "m/s/s", "default": 0.4, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.8 + "min": 0, + "max": 0.8 }, { "name": "EKF2_ABL_TAU", @@ -3056,8 +3056,8 @@ "units": "s", "default": 0.5, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "EKF2_ACC_B_NOISE", @@ -3068,8 +3068,8 @@ "units": "m/s**3", "default": 0.003, "decimalPlaces": 6, - "minValue": 0, - "maxValue": 0.01 + "min": 0, + "max": 0.01 }, { "name": "EKF2_ACC_NOISE", @@ -3080,8 +3080,8 @@ "units": "m/s/s", "default": 0.35, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 1 + "min": 0.01, + "max": 1 }, { "name": "EKF2_AID_MASK", @@ -3093,8 +3093,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 511 + "min": 0, + "max": 511 }, { "name": "EKF2_ANGERR_INIT", @@ -3106,8 +3106,8 @@ "default": 0.1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 0.5 + "min": 0, + "max": 0.5 }, { "name": "EKF2_ARSP_THR", @@ -3118,8 +3118,8 @@ "units": "m/s", "default": 0, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "EKF2_ASPD_MAX", @@ -3130,8 +3130,8 @@ "units": "m/s", "default": 20, "decimalPlaces": 1, - "minValue": 5, - "maxValue": 50 + "min": 5, + "max": 50 }, { "name": "EKF2_ASP_DELAY", @@ -3143,8 +3143,8 @@ "default": 100, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_AVEL_DELAY", @@ -3156,8 +3156,8 @@ "default": 5, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_BARO_DELAY", @@ -3169,8 +3169,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_BARO_GATE", @@ -3182,8 +3182,8 @@ "units": "SD", "default": 5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_BARO_NOISE", @@ -3194,8 +3194,8 @@ "units": "m", "default": 3.5, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 15 + "min": 0.01, + "max": 15 }, { "name": "EKF2_BCOEF_X", @@ -3206,8 +3206,8 @@ "units": "kg/m**2", "default": 25, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 100 + "min": 1, + "max": 100 }, { "name": "EKF2_BCOEF_Y", @@ -3218,8 +3218,8 @@ "units": "kg/m**2", "default": 25, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 100 + "min": 1, + "max": 100 }, { "name": "EKF2_BETA_GATE", @@ -3231,8 +3231,8 @@ "units": "SD", "default": 5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_BETA_NOISE", @@ -3243,8 +3243,8 @@ "units": "m/s", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "EKF2_DECL_TYPE", @@ -3256,8 +3256,8 @@ "default": 7, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 7 + "min": 0, + "max": 7 }, { "name": "EKF2_DRAG_NOISE", @@ -3268,8 +3268,8 @@ "units": "(m/sec**2)**2", "default": 2.5, "decimalPlaces": 2, - "minValue": 0.5, - "maxValue": 10 + "min": 0.5, + "max": 10 }, { "name": "EKF2_EAS_NOISE", @@ -3280,8 +3280,8 @@ "units": "m/s", "default": 1.4, "decimalPlaces": 1, - "minValue": 0.5, - "maxValue": 5 + "min": 0.5, + "max": 5 }, { "name": "EKF2_EVA_NOISE", @@ -3292,8 +3292,8 @@ "units": "rad", "default": 0.05, "decimalPlaces": 2, - "minValue": 0.05, - "maxValue": 3.40282e+38 + "min": 0.05, + "max": 3.40282e+38 }, { "name": "EKF2_EVP_GATE", @@ -3304,8 +3304,8 @@ "units": "SD", "default": 5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_EVP_NOISE", @@ -3316,8 +3316,8 @@ "units": "m", "default": 0.1, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "EKF2_EVV_GATE", @@ -3329,8 +3329,8 @@ "units": "SD", "default": 3, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_EVV_NOISE", @@ -3341,8 +3341,8 @@ "units": "m/s", "default": 0.1, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "EKF2_EV_DELAY", @@ -3354,8 +3354,8 @@ "default": 175, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_EV_NOISE_MD", @@ -3366,8 +3366,8 @@ "longDesc": "If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_EV_POS_X", @@ -3378,8 +3378,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_EV_POS_Y", @@ -3390,8 +3390,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_EV_POS_Z", @@ -3402,8 +3402,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_FUSE_BETA", @@ -3414,8 +3414,8 @@ "longDesc": "A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_GBIAS_INIT", @@ -3427,8 +3427,8 @@ "default": 0.1, "rebootRequired": true, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.2 + "min": 0, + "max": 0.2 }, { "name": "EKF2_GND_EFF_DZ", @@ -3440,8 +3440,8 @@ "units": "M", "default": 0, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "EKF2_GND_MAX_HGT", @@ -3453,8 +3453,8 @@ "units": "M", "default": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "EKF2_GPS_CHECK", @@ -3465,8 +3465,8 @@ "longDesc": "Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Minimum required PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT", "default": 245, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 511 + "min": 0, + "max": 511 }, { "name": "EKF2_GPS_DELAY", @@ -3478,8 +3478,8 @@ "default": 110, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_GPS_MASK", @@ -3490,8 +3490,8 @@ "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 7 + "min": 0, + "max": 7 }, { "name": "EKF2_GPS_POS_X", @@ -3502,8 +3502,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_GPS_POS_Y", @@ -3514,8 +3514,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_GPS_POS_Z", @@ -3526,8 +3526,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_GPS_P_GATE", @@ -3539,8 +3539,8 @@ "units": "SD", "default": 5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_GPS_P_NOISE", @@ -3551,8 +3551,8 @@ "units": "m", "default": 0.5, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 10 + "min": 0.01, + "max": 10 }, { "name": "EKF2_GPS_TAU", @@ -3564,8 +3564,8 @@ "units": "s", "default": 10, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 100 + "min": 1, + "max": 100 }, { "name": "EKF2_GPS_V_GATE", @@ -3577,8 +3577,8 @@ "units": "SD", "default": 5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_GPS_V_NOISE", @@ -3589,8 +3589,8 @@ "units": "m/s", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 5 + "min": 0.01, + "max": 5 }, { "name": "EKF2_GSF_TAS", @@ -3601,8 +3601,8 @@ "units": "m/s", "default": 15, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "EKF2_GYR_B_NOISE", @@ -3613,8 +3613,8 @@ "units": "rad/s**2", "default": 0.001, "decimalPlaces": 6, - "minValue": 0, - "maxValue": 0.01 + "min": 0, + "max": 0.01 }, { "name": "EKF2_GYR_NOISE", @@ -3625,8 +3625,8 @@ "units": "rad/s", "default": 0.015, "decimalPlaces": 4, - "minValue": 0.0001, - "maxValue": 0.1 + "min": 0.0001, + "max": 0.1 }, { "name": "EKF2_HDG_GATE", @@ -3638,8 +3638,8 @@ "units": "SD", "default": 2.6, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_HEAD_NOISE", @@ -3650,8 +3650,8 @@ "units": "rad", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 1 + "min": 0.01, + "max": 1 }, { "name": "EKF2_HGT_MODE", @@ -3681,8 +3681,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_IMU_ID", @@ -3699,8 +3699,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_IMU_POS_X", @@ -3711,8 +3711,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_IMU_POS_Y", @@ -3723,8 +3723,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_IMU_POS_Z", @@ -3735,8 +3735,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_MAGBIAS_ID", @@ -3747,8 +3747,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_MAGBIAS_X", @@ -3761,8 +3761,8 @@ "rebootRequired": true, "volatile": true, "decimalPlaces": 3, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_MAGBIAS_Y", @@ -3775,8 +3775,8 @@ "rebootRequired": true, "volatile": true, "decimalPlaces": 3, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_MAGBIAS_Z", @@ -3789,8 +3789,8 @@ "rebootRequired": true, "volatile": true, "decimalPlaces": 3, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_MAGB_K", @@ -3800,8 +3800,8 @@ "shortDesc": "Maximum fraction of learned mag bias saved at each disarm. Smaller values make the saved mag bias learn slower from flight to flight. Larger values make it learn faster. Must be > 0.0 and <= 1.0", "default": 0.2, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "EKF2_MAGB_VREF", @@ -3813,8 +3813,8 @@ "default": 2.5e-07, "rebootRequired": true, "decimalPlaces": 8, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_MAG_ACCLIM", @@ -3825,8 +3825,8 @@ "units": "m/s**2", "default": 0.5, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "EKF2_MAG_B_NOISE", @@ -3837,8 +3837,8 @@ "units": "Gauss/s", "default": 0.0001, "decimalPlaces": 6, - "minValue": 0, - "maxValue": 0.1 + "min": 0, + "max": 0.1 }, { "name": "EKF2_MAG_CHECK", @@ -3849,8 +3849,8 @@ "longDesc": "When set, the EKF checks the strength of the magnetic field to decide whether the magnetometer data is valid. If GPS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_MAG_DECL", @@ -3862,8 +3862,8 @@ "default": 0, "volatile": true, "decimalPlaces": 1, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_MAG_DELAY", @@ -3875,8 +3875,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_MAG_E_NOISE", @@ -3887,8 +3887,8 @@ "units": "Gauss/s", "default": 0.001, "decimalPlaces": 6, - "minValue": 0, - "maxValue": 0.1 + "min": 0, + "max": 0.1 }, { "name": "EKF2_MAG_GATE", @@ -3900,8 +3900,8 @@ "units": "SD", "default": 3, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_MAG_NOISE", @@ -3912,8 +3912,8 @@ "units": "Gauss", "default": 0.05, "decimalPlaces": 3, - "minValue": 0.001, - "maxValue": 1 + "min": 0.001, + "max": 1 }, { "name": "EKF2_MAG_TYPE", @@ -3951,8 +3951,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_MAG_YAWLIM", @@ -3963,8 +3963,8 @@ "units": "rad/s", "default": 0.25, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "EKF2_MIN_OBS_DT", @@ -3976,8 +3976,8 @@ "default": 20, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 10, - "maxValue": 50 + "min": 10, + "max": 50 }, { "name": "EKF2_MIN_RNG", @@ -3989,8 +3989,8 @@ "units": "m", "default": 0.1, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "EKF2_MOVE_TEST", @@ -4001,8 +4001,8 @@ "longDesc": "Scales the threshold tests applied to IMU data used to determine if the vehicle is static or moving. See parameter descriptions for EKF2_GPS_CHECK and EKF2_MAG_TYPE for further information on the functionality affected by this parameter.", "default": 1, "decimalPlaces": 1, - "minValue": 0.1, - "maxValue": 10 + "min": 0.1, + "max": 10 }, { "name": "EKF2_NOAID_NOISE", @@ -4013,8 +4013,8 @@ "units": "m", "default": 10, "decimalPlaces": 1, - "minValue": 0.5, - "maxValue": 50 + "min": 0.5, + "max": 50 }, { "name": "EKF2_NOAID_TOUT", @@ -4025,8 +4025,8 @@ "units": "uSec", "default": 5e+06, "decimalPlaces": 3, - "minValue": 500000, - "maxValue": 1e+07 + "min": 500000, + "max": 1e+07 }, { "name": "EKF2_OF_DELAY", @@ -4038,8 +4038,8 @@ "default": 5, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_OF_GATE", @@ -4051,8 +4051,8 @@ "units": "SD", "default": 3, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_OF_N_MAX", @@ -4064,8 +4064,8 @@ "units": "rad/s", "default": 0.5, "decimalPlaces": 2, - "minValue": 0.05, - "maxValue": 3.40282e+38 + "min": 0.05, + "max": 3.40282e+38 }, { "name": "EKF2_OF_N_MIN", @@ -4076,8 +4076,8 @@ "units": "rad/s", "default": 0.15, "decimalPlaces": 2, - "minValue": 0.05, - "maxValue": 3.40282e+38 + "min": 0.05, + "max": 3.40282e+38 }, { "name": "EKF2_OF_POS_X", @@ -4088,8 +4088,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_OF_POS_Y", @@ -4100,8 +4100,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_OF_POS_Z", @@ -4112,8 +4112,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_OF_QMIN", @@ -4123,8 +4123,8 @@ "shortDesc": "Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN", "default": 1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 255 + "min": 0, + "max": 255 }, { "name": "EKF2_PCOEF_XN", @@ -4134,8 +4134,8 @@ "shortDesc": "Static pressure position error coefficient for the negative X axis. This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number", "default": 0, "decimalPlaces": 2, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_PCOEF_XP", @@ -4145,8 +4145,8 @@ "shortDesc": "Static pressure position error coefficient for the positive X axis This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number", "default": 0, "decimalPlaces": 2, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_PCOEF_YN", @@ -4156,8 +4156,8 @@ "shortDesc": "Pressure position error coefficient for the negative Y axis. This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number", "default": 0, "decimalPlaces": 2, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_PCOEF_YP", @@ -4167,8 +4167,8 @@ "shortDesc": "Pressure position error coefficient for the positive Y axis. This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number", "default": 0, "decimalPlaces": 2, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_PCOEF_Z", @@ -4178,8 +4178,8 @@ "shortDesc": "Static pressure position error coefficient for the Z axis. This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis", "default": 0, "decimalPlaces": 2, - "minValue": -0.5, - "maxValue": 0.5 + "min": -0.5, + "max": 0.5 }, { "name": "EKF2_REQ_EPH", @@ -4190,8 +4190,8 @@ "units": "m", "default": 3, "decimalPlaces": 1, - "minValue": 2, - "maxValue": 100 + "min": 2, + "max": 100 }, { "name": "EKF2_REQ_EPV", @@ -4202,8 +4202,8 @@ "units": "m", "default": 5, "decimalPlaces": 1, - "minValue": 2, - "maxValue": 100 + "min": 2, + "max": 100 }, { "name": "EKF2_REQ_GPS_H", @@ -4216,8 +4216,8 @@ "default": 10, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0.1, - "maxValue": 3.40282e+38 + "min": 0.1, + "max": 3.40282e+38 }, { "name": "EKF2_REQ_HDRIFT", @@ -4228,8 +4228,8 @@ "units": "m/s", "default": 0.1, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "EKF2_REQ_NSATS", @@ -4239,8 +4239,8 @@ "shortDesc": "Required satellite count to use GPS", "default": 6, "decimalPlaces": 3, - "minValue": 4, - "maxValue": 12 + "min": 4, + "max": 12 }, { "name": "EKF2_REQ_PDOP", @@ -4250,8 +4250,8 @@ "shortDesc": "Required PDOP to use GPS", "default": 2.5, "decimalPlaces": 1, - "minValue": 1.5, - "maxValue": 5 + "min": 1.5, + "max": 5 }, { "name": "EKF2_REQ_SACC", @@ -4262,8 +4262,8 @@ "units": "m/s", "default": 0.5, "decimalPlaces": 2, - "minValue": 0.5, - "maxValue": 5 + "min": 0.5, + "max": 5 }, { "name": "EKF2_REQ_VDRIFT", @@ -4274,8 +4274,8 @@ "units": "m/s", "default": 0.2, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1.5 + "min": 0.1, + "max": 1.5 }, { "name": "EKF2_RNG_AID", @@ -4296,8 +4296,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EKF2_RNG_A_HMAX", @@ -4309,8 +4309,8 @@ "units": "m", "default": 5, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "EKF2_RNG_A_IGATE", @@ -4322,8 +4322,8 @@ "units": "SD", "default": 1, "decimalPlaces": 3, - "minValue": 0.1, - "maxValue": 5 + "min": 0.1, + "max": 5 }, { "name": "EKF2_RNG_A_VMAX", @@ -4335,8 +4335,8 @@ "units": "m/s", "default": 1, "decimalPlaces": 3, - "minValue": 0.1, - "maxValue": 2 + "min": 0.1, + "max": 2 }, { "name": "EKF2_RNG_DELAY", @@ -4348,8 +4348,8 @@ "default": 5, "rebootRequired": true, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "EKF2_RNG_GATE", @@ -4361,8 +4361,8 @@ "units": "SD", "default": 5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_RNG_NOISE", @@ -4373,8 +4373,8 @@ "units": "m", "default": 0.1, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "EKF2_RNG_PITCH", @@ -4385,8 +4385,8 @@ "units": "rad", "default": 0, "decimalPlaces": 3, - "minValue": -0.75, - "maxValue": 0.75 + "min": -0.75, + "max": 0.75 }, { "name": "EKF2_RNG_POS_X", @@ -4397,8 +4397,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_RNG_POS_Y", @@ -4409,8 +4409,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_RNG_POS_Z", @@ -4421,8 +4421,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EKF2_RNG_SFE", @@ -4434,8 +4434,8 @@ "units": "m/m", "default": 0.05, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 0.2 + "min": 0, + "max": 0.2 }, { "name": "EKF2_TAS_GATE", @@ -4447,8 +4447,8 @@ "units": "SD", "default": 3, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "EKF2_TAU_POS", @@ -4459,8 +4459,8 @@ "units": "s", "default": 0.25, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "EKF2_TAU_VEL", @@ -4471,8 +4471,8 @@ "units": "s", "default": 0.25, "decimalPlaces": 2, - "minValue": -3.40282e+38, - "maxValue": 1 + "min": -3.40282e+38, + "max": 1 }, { "name": "EKF2_TERR_GRAD", @@ -4483,8 +4483,8 @@ "units": "m/m", "default": 0.5, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "EKF2_TERR_MASK", @@ -4495,8 +4495,8 @@ "longDesc": "Set bits in the following positions to enable: 0 : Set to true to use range finder data if available 1 : Set to true to use optical flow data if available", "default": 3, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3 + "min": 0, + "max": 3 }, { "name": "EKF2_TERR_NOISE", @@ -4507,8 +4507,8 @@ "units": "m/s", "default": 5, "decimalPlaces": 1, - "minValue": 0.5, - "maxValue": 3.40282e+38 + "min": 0.5, + "max": 3.40282e+38 }, { "name": "EKF2_WIND_NOISE", @@ -4519,8 +4519,8 @@ "units": "m/s/s", "default": 0.1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "EV_TSK_RC_LOSS", @@ -4532,8 +4532,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EV_TSK_STAT_DIS", @@ -4545,8 +4545,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "EXFW_HDNG_P", @@ -4556,8 +4556,8 @@ "shortDesc": "EXFW_HDNG_P", "default": 0.1, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EXFW_PITCH_P", @@ -4567,8 +4567,8 @@ "shortDesc": "EXFW_PITCH_P", "default": 0.2, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "EXFW_ROLL_P", @@ -4578,8 +4578,8 @@ "shortDesc": "EXFW_ROLL_P", "default": 0.2, "decimalPlaces": 3, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "FD_ESCS_EN", @@ -4590,8 +4590,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FD_EXT_ATS_EN", @@ -4603,8 +4603,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FD_EXT_ATS_TRIG", @@ -4616,8 +4616,8 @@ "units": "microseconds", "default": 1900, "decimalPlaces": 2, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FD_FAIL_P", @@ -4629,8 +4629,8 @@ "units": "degrees", "default": 60, "decimalPlaces": 3, - "minValue": 60, - "maxValue": 180 + "min": 60, + "max": 180 }, { "name": "FD_FAIL_P_TTRI", @@ -4642,8 +4642,8 @@ "units": "s", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.02, - "maxValue": 5 + "min": 0.02, + "max": 5 }, { "name": "FD_FAIL_R", @@ -4655,8 +4655,8 @@ "units": "degrees", "default": 60, "decimalPlaces": 3, - "minValue": 60, - "maxValue": 180 + "min": 60, + "max": 180 }, { "name": "FD_FAIL_R_TTRI", @@ -4668,8 +4668,8 @@ "units": "s", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.02, - "maxValue": 5 + "min": 0.02, + "max": 5 }, { "name": "FW_ACRO_X_MAX", @@ -4681,8 +4681,8 @@ "units": "degrees", "default": 90, "decimalPlaces": 3, - "minValue": 45, - "maxValue": 720 + "min": 45, + "max": 720 }, { "name": "FW_ACRO_Y_MAX", @@ -4694,8 +4694,8 @@ "units": "degrees", "default": 90, "decimalPlaces": 3, - "minValue": 45, - "maxValue": 720 + "min": 45, + "max": 720 }, { "name": "FW_ACRO_Z_MAX", @@ -4707,8 +4707,8 @@ "units": "degrees", "default": 45, "decimalPlaces": 3, - "minValue": 10, - "maxValue": 180 + "min": 10, + "max": 180 }, { "name": "FW_AIRSPD_MAX", @@ -4721,8 +4721,8 @@ "default": 20, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 40 + "min": 0, + "max": 40 }, { "name": "FW_AIRSPD_MIN", @@ -4735,8 +4735,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 40 + "min": 0, + "max": 40 }, { "name": "FW_AIRSPD_TRIM", @@ -4749,8 +4749,8 @@ "default": 15, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 40 + "min": 0, + "max": 40 }, { "name": "FW_ARSP_MODE", @@ -4771,8 +4771,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FW_ARSP_SCALE_EN", @@ -4783,8 +4783,8 @@ "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FW_BAT_SCALE_EN", @@ -4795,8 +4795,8 @@ "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FW_CLMBOUT_DIFF", @@ -4809,8 +4809,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 150 + "min": 0, + "max": 150 }, { "name": "FW_DTRIM_P_FLPS", @@ -4822,8 +4822,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_P_VMAX", @@ -4835,8 +4835,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_P_VMIN", @@ -4848,8 +4848,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_R_FLPS", @@ -4861,8 +4861,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_R_VMAX", @@ -4874,8 +4874,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_R_VMIN", @@ -4887,8 +4887,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_Y_VMAX", @@ -4900,8 +4900,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_DTRIM_Y_VMIN", @@ -4913,8 +4913,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": -0.25, - "maxValue": 0.25 + "min": -0.25, + "max": 0.25 }, { "name": "FW_FLAPERON_SCL", @@ -4926,8 +4926,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_FLAPS_LND_SCL", @@ -4940,8 +4940,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_FLAPS_SCL", @@ -4953,8 +4953,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_FLAPS_TO_SCL", @@ -4967,8 +4967,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_GND_SPD_MIN", @@ -4981,8 +4981,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 40 + "min": 0, + "max": 40 }, { "name": "FW_L1_DAMPING", @@ -4994,8 +4994,8 @@ "default": 0.75, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.6, - "maxValue": 0.9 + "min": 0.6, + "max": 0.9 }, { "name": "FW_L1_PERIOD", @@ -5008,8 +5008,8 @@ "default": 20, "increment": 0.5, "decimalPlaces": 1, - "minValue": 12, - "maxValue": 50 + "min": 12, + "max": 50 }, { "name": "FW_L1_R_SLEW_MAX", @@ -5022,8 +5022,8 @@ "default": 90, "increment": 1, "decimalPlaces": 0, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "FW_LND_AIRSPD_SC", @@ -5036,8 +5036,8 @@ "default": 1.3, "increment": 0.01, "decimalPlaces": 2, - "minValue": 1, - "maxValue": 1.5 + "min": 1, + "max": 1.5 }, { "name": "FW_LND_ANG", @@ -5049,8 +5049,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 15 + "min": 1, + "max": 15 }, { "name": "FW_LND_EARLYCFG", @@ -5061,8 +5061,8 @@ "longDesc": "When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FW_LND_FLALT", @@ -5074,8 +5074,8 @@ "default": 3, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 25 + "min": 0, + "max": 25 }, { "name": "FW_LND_FL_PMAX", @@ -5088,8 +5088,8 @@ "default": 15, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 45 + "min": 0, + "max": 45 }, { "name": "FW_LND_FL_PMIN", @@ -5102,8 +5102,8 @@ "default": 2.5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 15 + "min": 0, + "max": 15 }, { "name": "FW_LND_HHDIST", @@ -5115,8 +5115,8 @@ "default": 15, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 30 + "min": 0, + "max": 30 }, { "name": "FW_LND_HVIRT", @@ -5128,8 +5128,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 15 + "min": 1, + "max": 15 }, { "name": "FW_LND_THRTC_SC", @@ -5141,8 +5141,8 @@ "default": 1, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0.2, - "maxValue": 1 + "min": 0.2, + "max": 1 }, { "name": "FW_LND_TLALT", @@ -5155,8 +5155,8 @@ "default": -1, "increment": 0.5, "decimalPlaces": 1, - "minValue": -1, - "maxValue": 30 + "min": -1, + "max": 30 }, { "name": "FW_LND_USETER", @@ -5167,8 +5167,8 @@ "longDesc": "This is turned off by default and a waypoint or return altitude is normally used (or sea level for an arbitrary land position).", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FW_MAN_P_MAX", @@ -5181,8 +5181,8 @@ "default": 45, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "FW_MAN_P_SC", @@ -5195,8 +5195,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "FW_MAN_R_MAX", @@ -5209,8 +5209,8 @@ "default": 45, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "FW_MAN_R_SC", @@ -5223,8 +5223,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_MAN_Y_SC", @@ -5237,8 +5237,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "FW_PR_FF", @@ -5251,8 +5251,8 @@ "default": 0.5, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "FW_PR_I", @@ -5265,8 +5265,8 @@ "default": 0.1, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 0.5 + "min": 0.005, + "max": 0.5 }, { "name": "FW_PR_IMAX", @@ -5278,8 +5278,8 @@ "default": 0.4, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_PR_P", @@ -5292,8 +5292,8 @@ "default": 0.08, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 1 + "min": 0.005, + "max": 1 }, { "name": "FW_PSP_OFF", @@ -5306,8 +5306,8 @@ "default": 0, "increment": 0.5, "decimalPlaces": 1, - "minValue": -90, - "maxValue": 90 + "min": -90, + "max": 90 }, { "name": "FW_P_LIM_MAX", @@ -5320,8 +5320,8 @@ "default": 45, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 60 + "min": 0, + "max": 60 }, { "name": "FW_P_LIM_MIN", @@ -5334,8 +5334,8 @@ "default": -45, "increment": 0.5, "decimalPlaces": 1, - "minValue": -60, - "maxValue": 0 + "min": -60, + "max": 0 }, { "name": "FW_P_RMAX_NEG", @@ -5348,8 +5348,8 @@ "default": 60, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "FW_P_RMAX_POS", @@ -5362,8 +5362,8 @@ "default": 60, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "FW_P_TC", @@ -5376,8 +5376,8 @@ "default": 0.4, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.2, - "maxValue": 1 + "min": 0.2, + "max": 1 }, { "name": "FW_RATT_TH", @@ -5389,8 +5389,8 @@ "default": 0.8, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_RLL_TO_YAW_FF", @@ -5402,8 +5402,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "FW_RR_FF", @@ -5416,8 +5416,8 @@ "default": 0.5, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "FW_RR_I", @@ -5430,8 +5430,8 @@ "default": 0.1, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 0.2 + "min": 0.005, + "max": 0.2 }, { "name": "FW_RR_IMAX", @@ -5443,8 +5443,8 @@ "default": 0.2, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_RR_P", @@ -5457,8 +5457,8 @@ "default": 0.05, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 1 + "min": 0.005, + "max": 1 }, { "name": "FW_RSP_OFF", @@ -5471,8 +5471,8 @@ "default": 0, "increment": 0.5, "decimalPlaces": 1, - "minValue": -90, - "maxValue": 90 + "min": -90, + "max": 90 }, { "name": "FW_R_LIM", @@ -5485,8 +5485,8 @@ "default": 50, "increment": 0.5, "decimalPlaces": 1, - "minValue": 35, - "maxValue": 65 + "min": 35, + "max": 65 }, { "name": "FW_R_RMAX", @@ -5499,8 +5499,8 @@ "default": 70, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "FW_R_TC", @@ -5513,8 +5513,8 @@ "default": 0.4, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.4, - "maxValue": 1 + "min": 0.4, + "max": 1 }, { "name": "FW_THR_ALT_SCL", @@ -5526,8 +5526,8 @@ "default": 0, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "FW_THR_CRUISE", @@ -5540,8 +5540,8 @@ "default": 0.6, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_THR_IDLE", @@ -5554,8 +5554,8 @@ "default": 0.15, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.4 + "min": 0, + "max": 0.4 }, { "name": "FW_THR_LND_MAX", @@ -5568,8 +5568,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_THR_MAX", @@ -5582,8 +5582,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_THR_MIN", @@ -5596,8 +5596,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_THR_SLEW_MAX", @@ -5608,8 +5608,8 @@ "longDesc": "Maximum slew rate for the commanded throttle", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_T_CLMB_MAX", @@ -5622,8 +5622,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 15 + "min": 1, + "max": 15 }, { "name": "FW_T_HRATE_FF", @@ -5634,8 +5634,8 @@ "default": 0.8, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_T_HRATE_P", @@ -5646,8 +5646,8 @@ "default": 0.05, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_T_INTEG_GAIN", @@ -5659,8 +5659,8 @@ "default": 0.1, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "FW_T_PTCH_DAMP", @@ -5672,8 +5672,8 @@ "default": 0, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "FW_T_RLL2THR", @@ -5685,8 +5685,8 @@ "default": 15, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 20 + "min": 0, + "max": 20 }, { "name": "FW_T_SINK_MAX", @@ -5699,8 +5699,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 15 + "min": 1, + "max": 15 }, { "name": "FW_T_SINK_MIN", @@ -5713,8 +5713,8 @@ "default": 2, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 5 + "min": 1, + "max": 5 }, { "name": "FW_T_SPDWEIGHT", @@ -5726,8 +5726,8 @@ "default": 1, "increment": 1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "FW_T_SPD_OMEGA", @@ -5740,8 +5740,8 @@ "default": 2, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "FW_T_SRATE_P", @@ -5752,8 +5752,8 @@ "default": 0.02, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "FW_T_THRO_CONST", @@ -5766,8 +5766,8 @@ "default": 8, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "FW_T_THR_DAMP", @@ -5779,8 +5779,8 @@ "default": 0.5, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "FW_T_TIME_CONST", @@ -5793,8 +5793,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "FW_T_VERT_ACC", @@ -5807,8 +5807,8 @@ "default": 7, "increment": 0.5, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "FW_WR_FF", @@ -5821,8 +5821,8 @@ "default": 0.2, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "FW_WR_I", @@ -5835,8 +5835,8 @@ "default": 0.1, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 0.5 + "min": 0.005, + "max": 0.5 }, { "name": "FW_WR_IMAX", @@ -5848,8 +5848,8 @@ "default": 1, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_WR_P", @@ -5862,8 +5862,8 @@ "default": 0.5, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 1 + "min": 0.005, + "max": 1 }, { "name": "FW_W_EN", @@ -5873,8 +5873,8 @@ "shortDesc": "Enable wheel steering controller", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "FW_W_RMAX", @@ -5887,8 +5887,8 @@ "default": 30, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "FW_YR_FF", @@ -5901,8 +5901,8 @@ "default": 0.3, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "FW_YR_I", @@ -5915,8 +5915,8 @@ "default": 0.1, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 50 + "min": 0, + "max": 50 }, { "name": "FW_YR_IMAX", @@ -5928,8 +5928,8 @@ "default": 0.2, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "FW_YR_P", @@ -5942,8 +5942,8 @@ "default": 0.05, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 1 + "min": 0.005, + "max": 1 }, { "name": "FW_Y_RMAX", @@ -5956,8 +5956,8 @@ "default": 50, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "GF_ACTION", @@ -5990,8 +5990,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 4 + "min": 0, + "max": 4 }, { "name": "GF_ALTMODE", @@ -6012,8 +6012,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GF_COUNT", @@ -6025,8 +6025,8 @@ "default": -1, "increment": 1, "decimalPlaces": 0, - "minValue": -1, - "maxValue": 10 + "min": -1, + "max": 10 }, { "name": "GF_MAX_HOR_DIST", @@ -6039,8 +6039,8 @@ "default": 0, "increment": 1, "decimalPlaces": 0, - "minValue": 0, - "maxValue": 10000 + "min": 0, + "max": 10000 }, { "name": "GF_MAX_VER_DIST", @@ -6053,8 +6053,8 @@ "default": 0, "increment": 1, "decimalPlaces": 0, - "minValue": 0, - "maxValue": 10000 + "min": 0, + "max": 10000 }, { "name": "GF_SOURCE", @@ -6075,8 +6075,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GND_L1_DAMPING", @@ -6088,8 +6088,8 @@ "default": 0.75, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0.6, - "maxValue": 0.9 + "min": 0.6, + "max": 0.9 }, { "name": "GND_L1_DIST", @@ -6102,8 +6102,8 @@ "default": 5, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "GND_L1_PERIOD", @@ -6116,8 +6116,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 50 + "min": 0, + "max": 50 }, { "name": "GND_MAX_ANG", @@ -6129,8 +6129,8 @@ "default": 0.7854, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3.14159 + "min": 0, + "max": 3.14159 }, { "name": "GND_SPEED_D", @@ -6143,8 +6143,8 @@ "default": 0.001, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 50 + "min": 0, + "max": 50 }, { "name": "GND_SPEED_I", @@ -6157,8 +6157,8 @@ "default": 3, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 50 + "min": 0, + "max": 50 }, { "name": "GND_SPEED_IMAX", @@ -6171,8 +6171,8 @@ "default": 1, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 50 + "min": 0.005, + "max": 50 }, { "name": "GND_SPEED_MAX", @@ -6184,8 +6184,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 40 + "min": 0, + "max": 40 }, { "name": "GND_SPEED_P", @@ -6198,8 +6198,8 @@ "default": 2, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 50 + "min": 0.005, + "max": 50 }, { "name": "GND_SPEED_THR_SC", @@ -6212,8 +6212,8 @@ "default": 1, "increment": 0.005, "decimalPlaces": 3, - "minValue": 0.005, - "maxValue": 50 + "min": 0.005, + "max": 50 }, { "name": "GND_SPEED_TRIM", @@ -6225,8 +6225,8 @@ "default": 3, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 40 + "min": 0, + "max": 40 }, { "name": "GND_SP_CTRL_MODE", @@ -6247,8 +6247,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GND_THR_CRUISE", @@ -6261,8 +6261,8 @@ "default": 0.1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GND_THR_IDLE", @@ -6275,8 +6275,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.4 + "min": 0, + "max": 0.4 }, { "name": "GND_THR_MAX", @@ -6289,8 +6289,8 @@ "default": 0.3, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GND_THR_MIN", @@ -6303,8 +6303,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GND_WHEEL_BASE", @@ -6316,8 +6316,8 @@ "default": 2, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "GPS_{n}_CONFIG", @@ -6371,8 +6371,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "GPS_DUMP_COMM", @@ -6393,8 +6393,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "GPS_UBX_DYNMODEL", @@ -6428,8 +6428,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 9 + "min": 0, + "max": 9 }, { "name": "GPS_YAW_OFFSET", @@ -6442,8 +6442,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 0, - "minValue": 0, - "maxValue": 360 + "min": 0, + "max": 360 }, { "name": "HTE_ACC_GATE", @@ -6455,8 +6455,8 @@ "units": "SD", "default": 3, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 10 + "min": 1, + "max": 10 }, { "name": "HTE_HT_ERR_INIT", @@ -6468,8 +6468,8 @@ "units": "normalized_thrust", "default": 0.1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "HTE_HT_NOISE", @@ -6481,8 +6481,8 @@ "units": "normalized_thrust/s", "default": 0.0005, "decimalPlaces": 4, - "minValue": 0.0001, - "maxValue": 1 + "min": 0.0001, + "max": 1 }, { "name": "IMU_ACCEL_CUTOFF", @@ -6495,8 +6495,8 @@ "default": 30, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1000 + "min": 0, + "max": 1000 }, { "name": "IMU_DGYRO_CUTOFF", @@ -6509,8 +6509,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1000 + "min": 0, + "max": 1000 }, { "name": "IMU_GYRO_CUTOFF", @@ -6523,8 +6523,8 @@ "default": 30, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1000 + "min": 0, + "max": 1000 }, { "name": "IMU_GYRO_NF_BW", @@ -6537,8 +6537,8 @@ "default": 20, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "IMU_GYRO_NF_FREQ", @@ -6551,8 +6551,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1000 + "min": 0, + "max": 1000 }, { "name": "IMU_GYRO_RATEMAX", @@ -6591,8 +6591,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2000 + "min": 0, + "max": 2000 }, { "name": "IMU_INTEG_RATE", @@ -6605,8 +6605,8 @@ "default": 200, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 100, - "maxValue": 1000 + "min": 100, + "max": 1000 }, { "name": "INA226_CONFIG", @@ -6618,8 +6618,8 @@ "default": 18139, "increment": 1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 65535 + "min": 0, + "max": 65535 }, { "name": "INA226_CURRENT", @@ -6630,8 +6630,8 @@ "default": 164, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 200 + "min": 0.1, + "max": 200 }, { "name": "INA226_SHUNT", @@ -6642,8 +6642,8 @@ "default": 0.0005, "increment": 1e-09, "decimalPlaces": 10, - "minValue": 1e-09, - "maxValue": 0.1 + "min": 1e-09, + "max": 0.1 }, { "name": "ISBD_CONFIG", @@ -6697,8 +6697,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "ISBD_READ_INT", @@ -6709,8 +6709,8 @@ "units": "s", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 5000 + "min": 0, + "max": 5000 }, { "name": "ISBD_SBD_TIMEOUT", @@ -6721,8 +6721,8 @@ "units": "s", "default": 60, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 300 + "min": 0, + "max": 300 }, { "name": "ISBD_STACK_TIME", @@ -6733,8 +6733,8 @@ "units": "ms", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 500 + "min": 0, + "max": 500 }, { "name": "LAUN_ALL_ON", @@ -6744,8 +6744,8 @@ "shortDesc": "Launch detection", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "LAUN_CAT_A", @@ -6758,8 +6758,8 @@ "default": 30, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "LAUN_CAT_MDEL", @@ -6772,8 +6772,8 @@ "default": 0, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "LAUN_CAT_PMAX", @@ -6786,8 +6786,8 @@ "default": 30, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 45 + "min": 0, + "max": 45 }, { "name": "LAUN_CAT_T", @@ -6800,8 +6800,8 @@ "default": 0.05, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "LED_RGB1_MAXBRT", @@ -6812,8 +6812,8 @@ "longDesc": "Set to 0 to disable, 1 for minimum brightness up to 31 (max)", "default": 31, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 31 + "min": 0, + "max": 31 }, { "name": "LED_RGB_MAXBRT", @@ -6824,8 +6824,8 @@ "longDesc": "Set to 0 to disable, 1 for minimum brightness up to 15 (max)", "default": 15, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 15 + "min": 0, + "max": 15 }, { "name": "LIGHT_EN_BLINKM", @@ -6836,8 +6836,8 @@ "default": 0, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "LNDFW_AIRSPD_MAX", @@ -6849,8 +6849,8 @@ "units": "m/s", "default": 8, "decimalPlaces": 1, - "minValue": 4, - "maxValue": 20 + "min": 4, + "max": 20 }, { "name": "LNDFW_VEL_XY_MAX", @@ -6862,8 +6862,8 @@ "units": "m/s", "default": 5, "decimalPlaces": 1, - "minValue": 0.5, - "maxValue": 10 + "min": 0.5, + "max": 10 }, { "name": "LNDFW_VEL_Z_MAX", @@ -6875,8 +6875,8 @@ "units": "m/s", "default": 3, "decimalPlaces": 1, - "minValue": 0.1, - "maxValue": 20 + "min": 0.1, + "max": 20 }, { "name": "LNDFW_XYACC_MAX", @@ -6888,8 +6888,8 @@ "units": "m/s^2", "default": 8, "decimalPlaces": 1, - "minValue": 2, - "maxValue": 15 + "min": 2, + "max": 15 }, { "name": "LNDMC_ALT_MAX", @@ -6901,8 +6901,8 @@ "units": "m", "default": -1, "decimalPlaces": 2, - "minValue": -1, - "maxValue": 10000 + "min": -1, + "max": 10000 }, { "name": "LNDMC_FFALL_THR", @@ -6914,8 +6914,8 @@ "units": "m/s^2", "default": 2, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 10 + "min": 0.1, + "max": 10 }, { "name": "LNDMC_FFALL_TTRI", @@ -6927,8 +6927,8 @@ "units": "s", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.02, - "maxValue": 5 + "min": 0.02, + "max": 5 }, { "name": "LNDMC_LOW_T_THR", @@ -6940,8 +6940,8 @@ "units": "norm", "default": 0.3, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 0.9 + "min": 0.1, + "max": 0.9 }, { "name": "LNDMC_ROT_MAX", @@ -6953,8 +6953,8 @@ "units": "deg/s", "default": 20, "decimalPlaces": 1, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "LNDMC_XY_VEL_MAX", @@ -6966,8 +6966,8 @@ "units": "m/s", "default": 1.5, "decimalPlaces": 1, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "LNDMC_Z_VEL_MAX", @@ -6979,8 +6979,8 @@ "units": "m/s", "default": 0.5, "decimalPlaces": 1, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "LND_FLIGHT_T_HI", @@ -6992,8 +6992,8 @@ "default": 0, "volatile": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2.14748e+09 + "min": 0, + "max": 2.14748e+09 }, { "name": "LND_FLIGHT_T_LO", @@ -7005,8 +7005,8 @@ "default": 0, "volatile": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2.14748e+09 + "min": 0, + "max": 2.14748e+09 }, { "name": "LPE_ACC_XY", @@ -7018,8 +7018,8 @@ "units": "m/s^2/sqrt(Hz)", "default": 0.012, "decimalPlaces": 4, - "minValue": 1e-05, - "maxValue": 2 + "min": 1e-05, + "max": 2 }, { "name": "LPE_ACC_Z", @@ -7031,8 +7031,8 @@ "units": "m/s^2/sqrt(Hz)", "default": 0.02, "decimalPlaces": 4, - "minValue": 1e-05, - "maxValue": 2 + "min": 1e-05, + "max": 2 }, { "name": "LPE_BAR_Z", @@ -7043,8 +7043,8 @@ "units": "m", "default": 3, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 100 + "min": 0.01, + "max": 100 }, { "name": "LPE_EPH_MAX", @@ -7055,8 +7055,8 @@ "units": "m", "default": 3, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 5 + "min": 1, + "max": 5 }, { "name": "LPE_EPV_MAX", @@ -7067,8 +7067,8 @@ "units": "m", "default": 5, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 5 + "min": 1, + "max": 5 }, { "name": "LPE_FAKE_ORIGIN", @@ -7078,8 +7078,8 @@ "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "LPE_FGYRO_HP", @@ -7090,8 +7090,8 @@ "units": "Hz", "default": 0.001, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "LPE_FLW_OFF_Z", @@ -7102,8 +7102,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 1 + "min": -1, + "max": 1 }, { "name": "LPE_FLW_QMIN", @@ -7113,8 +7113,8 @@ "shortDesc": "Optical flow minimum quality threshold", "default": 150, "decimalPlaces": 0, - "minValue": 0, - "maxValue": 255 + "min": 0, + "max": 255 }, { "name": "LPE_FLW_R", @@ -7125,8 +7125,8 @@ "units": "m/s / (rad)", "default": 7, "decimalPlaces": 3, - "minValue": 0.1, - "maxValue": 10 + "min": 0.1, + "max": 10 }, { "name": "LPE_FLW_RR", @@ -7137,8 +7137,8 @@ "units": "m/s / (rad/s)", "default": 7, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "LPE_FLW_SCALE", @@ -7149,8 +7149,8 @@ "units": "m", "default": 1.3, "decimalPlaces": 3, - "minValue": 0.1, - "maxValue": 10 + "min": 0.1, + "max": 10 }, { "name": "LPE_FUSION", @@ -7161,8 +7161,8 @@ "longDesc": "Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)", "default": 145, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 255 + "min": 0, + "max": 255 }, { "name": "LPE_GPS_DELAY", @@ -7173,8 +7173,8 @@ "units": "sec", "default": 0.29, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.4 + "min": 0, + "max": 0.4 }, { "name": "LPE_GPS_VXY", @@ -7185,8 +7185,8 @@ "units": "m/s", "default": 0.25, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 2 + "min": 0.01, + "max": 2 }, { "name": "LPE_GPS_VZ", @@ -7197,8 +7197,8 @@ "units": "m/s", "default": 0.25, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 2 + "min": 0.01, + "max": 2 }, { "name": "LPE_GPS_XY", @@ -7209,8 +7209,8 @@ "units": "m", "default": 1, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 5 + "min": 0.01, + "max": 5 }, { "name": "LPE_GPS_Z", @@ -7221,8 +7221,8 @@ "units": "m", "default": 3, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 200 + "min": 0.01, + "max": 200 }, { "name": "LPE_LAND_VXY", @@ -7233,8 +7233,8 @@ "units": "m/s", "default": 0.05, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 10 + "min": 0.01, + "max": 10 }, { "name": "LPE_LAND_Z", @@ -7245,8 +7245,8 @@ "units": "m", "default": 0.03, "decimalPlaces": 3, - "minValue": 0.001, - "maxValue": 10 + "min": 0.001, + "max": 10 }, { "name": "LPE_LAT", @@ -7257,8 +7257,8 @@ "units": "deg", "default": 47.3977, "decimalPlaces": 8, - "minValue": -90, - "maxValue": 90 + "min": -90, + "max": 90 }, { "name": "LPE_LDR_OFF_Z", @@ -7269,8 +7269,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 1 + "min": -1, + "max": 1 }, { "name": "LPE_LDR_Z", @@ -7281,8 +7281,8 @@ "units": "m", "default": 0.03, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 1 + "min": 0.01, + "max": 1 }, { "name": "LPE_LON", @@ -7293,8 +7293,8 @@ "units": "deg", "default": 8.54559, "decimalPlaces": 8, - "minValue": -180, - "maxValue": 180 + "min": -180, + "max": 180 }, { "name": "LPE_LT_COV", @@ -7305,8 +7305,8 @@ "units": "m^2", "default": 0.0001, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "LPE_PN_B", @@ -7317,8 +7317,8 @@ "units": "(m/s^2)/s/sqrt(Hz)", "default": 0.001, "decimalPlaces": 8, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "LPE_PN_P", @@ -7330,8 +7330,8 @@ "units": "m/s/sqrt(Hz)", "default": 0.1, "decimalPlaces": 8, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "LPE_PN_T", @@ -7342,8 +7342,8 @@ "units": "(m/s)/(sqrt(hz))", "default": 0.001, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "LPE_PN_V", @@ -7355,8 +7355,8 @@ "units": "(m/s)/s/sqrt(Hz)", "default": 0.1, "decimalPlaces": 8, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "LPE_SNR_OFF_Z", @@ -7367,8 +7367,8 @@ "units": "m", "default": 0, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 1 + "min": -1, + "max": 1 }, { "name": "LPE_SNR_Z", @@ -7379,8 +7379,8 @@ "units": "m", "default": 0.05, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 1 + "min": 0.01, + "max": 1 }, { "name": "LPE_T_MAX_GRADE", @@ -7391,8 +7391,8 @@ "units": "%", "default": 1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "LPE_VIC_P", @@ -7403,8 +7403,8 @@ "units": "m", "default": 0.001, "decimalPlaces": 4, - "minValue": 0.0001, - "maxValue": 1 + "min": 0.0001, + "max": 1 }, { "name": "LPE_VIS_DELAY", @@ -7416,8 +7416,8 @@ "units": "sec", "default": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.1 + "min": 0, + "max": 0.1 }, { "name": "LPE_VIS_XY", @@ -7428,8 +7428,8 @@ "units": "m", "default": 0.1, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 1 + "min": 0.01, + "max": 1 }, { "name": "LPE_VIS_Z", @@ -7440,8 +7440,8 @@ "units": "m", "default": 0.5, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 100 + "min": 0.01, + "max": 100 }, { "name": "LPE_VXY_PUB", @@ -7452,8 +7452,8 @@ "units": "m/s", "default": 0.3, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 1 + "min": 0.01, + "max": 1 }, { "name": "LPE_X_LP", @@ -7464,8 +7464,8 @@ "units": "Hz", "default": 5, "decimalPlaces": 0, - "minValue": 5, - "maxValue": 1000 + "min": 5, + "max": 1000 }, { "name": "LPE_Z_PUB", @@ -7476,8 +7476,8 @@ "units": "m", "default": 1, "decimalPlaces": 1, - "minValue": 0.3, - "maxValue": 5 + "min": 0.3, + "max": 5 }, { "name": "LTEST_ACC_UNC", @@ -7489,8 +7489,8 @@ "units": "(m/s^2)^2", "default": 10, "decimalPlaces": 2, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "LTEST_MEAS_UNC", @@ -7502,8 +7502,8 @@ "units": "tan(rad)^2", "default": 0.005, "decimalPlaces": 4, - "minValue": -3.40282e+38, - "maxValue": 3.40282e+38 + "min": -3.40282e+38, + "max": 3.40282e+38 }, { "name": "LTEST_MODE", @@ -7524,8 +7524,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "LTEST_POS_UNC_IN", @@ -7537,8 +7537,8 @@ "units": "m^2", "default": 0.1, "decimalPlaces": 3, - "minValue": 0.001, - "maxValue": 3.40282e+38 + "min": 0.001, + "max": 3.40282e+38 }, { "name": "LTEST_SCALE_X", @@ -7549,8 +7549,8 @@ "longDesc": "Landing target x measurements are scaled by this factor before being used", "default": 1, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "LTEST_SCALE_Y", @@ -7561,8 +7561,8 @@ "longDesc": "Landing target y measurements are scaled by this factor before being used", "default": 1, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 3.40282e+38 + "min": 0.01, + "max": 3.40282e+38 }, { "name": "LTEST_VEL_UNC_IN", @@ -7574,8 +7574,8 @@ "units": "(m/s)^2", "default": 0.1, "decimalPlaces": 3, - "minValue": 0.001, - "maxValue": 3.40282e+38 + "min": 0.001, + "max": 3.40282e+38 }, { "name": "MAV_{n}_CONFIG", @@ -7629,8 +7629,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_{n}_FORWARD", @@ -7642,8 +7642,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_{n}_MODE", @@ -7689,8 +7689,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_{n}_RADIO_CTL", @@ -7702,8 +7702,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_{n}_RATE", @@ -7716,8 +7716,8 @@ "default": 1200, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2.14748e+09 + "min": 0, + "max": 2.14748e+09 }, { "name": "MAV_BROADCAST", @@ -7742,8 +7742,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_COMP_ID", @@ -7754,8 +7754,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 250 + "min": 1, + "max": 250 }, { "name": "MAV_FWDEXTSP", @@ -7766,8 +7766,8 @@ "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_HASH_CHK_EN", @@ -7778,8 +7778,8 @@ "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_HB_FORW_EN", @@ -7790,8 +7790,8 @@ "longDesc": "The mavlink hearbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_ODOM_LP", @@ -7802,8 +7802,8 @@ "longDesc": "If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry' serving as a loopback of the received ODOMETRY messages on the Mavlink receiver.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_PROTO_VER", @@ -7827,8 +7827,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MAV_RADIO_TOUT", @@ -7840,8 +7840,8 @@ "units": "s", "default": 5, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 250 + "min": 1, + "max": 250 }, { "name": "MAV_SIK_RADIO_ID", @@ -7852,8 +7852,8 @@ "longDesc": "When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio", "default": 0, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 240 + "min": -1, + "max": 240 }, { "name": "MAV_SYS_ID", @@ -7864,8 +7864,8 @@ "default": 1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 250 + "min": 1, + "max": 250 }, { "name": "MAV_TYPE", @@ -7985,8 +7985,8 @@ } ], "decimalPlaces": 3, - "minValue": 1, - "maxValue": 27 + "min": 1, + "max": 27 }, { "name": "MAV_USEHILGPS", @@ -7997,8 +7997,8 @@ "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MC_ACRO_EXPO", @@ -8009,8 +8009,8 @@ "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "default": 0.69, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MC_ACRO_EXPO_Y", @@ -8021,8 +8021,8 @@ "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "default": 0.69, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MC_ACRO_P_MAX", @@ -8034,8 +8034,8 @@ "default": 720, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 1800 + "min": 0, + "max": 1800 }, { "name": "MC_ACRO_R_MAX", @@ -8047,8 +8047,8 @@ "default": 720, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 1800 + "min": 0, + "max": 1800 }, { "name": "MC_ACRO_SUPEXPO", @@ -8059,8 +8059,8 @@ "longDesc": "SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "default": 0.7, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.95 + "min": 0, + "max": 0.95 }, { "name": "MC_ACRO_SUPEXPOY", @@ -8071,8 +8071,8 @@ "longDesc": "SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "default": 0.7, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.95 + "min": 0, + "max": 0.95 }, { "name": "MC_ACRO_Y_MAX", @@ -8084,8 +8084,8 @@ "default": 540, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 1800 + "min": 0, + "max": 1800 }, { "name": "MC_AIRMODE", @@ -8110,8 +8110,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MC_BAT_SCALE_EN", @@ -8122,8 +8122,8 @@ "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MC_MAN_TILT_TAU", @@ -8134,8 +8134,8 @@ "units": "s", "default": 0, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "MC_PITCHRATE_D", @@ -8147,8 +8147,8 @@ "default": 0.003, "increment": 0.0005, "decimalPlaces": 4, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_PITCHRATE_FF", @@ -8159,8 +8159,8 @@ "longDesc": "Improves tracking performance.", "default": 0, "decimalPlaces": 4, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_PITCHRATE_I", @@ -8172,8 +8172,8 @@ "default": 0.2, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_PITCHRATE_K", @@ -8185,8 +8185,8 @@ "default": 1, "increment": 0.0005, "decimalPlaces": 4, - "minValue": 0.01, - "maxValue": 5 + "min": 0.01, + "max": 5 }, { "name": "MC_PITCHRATE_MAX", @@ -8199,8 +8199,8 @@ "default": 220, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 1800 + "min": 0, + "max": 1800 }, { "name": "MC_PITCHRATE_P", @@ -8212,8 +8212,8 @@ "default": 0.15, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 0.6 + "min": 0.01, + "max": 0.6 }, { "name": "MC_PITCH_P", @@ -8226,8 +8226,8 @@ "default": 6.5, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 12 + "min": 0, + "max": 12 }, { "name": "MC_PR_INT_LIM", @@ -8239,8 +8239,8 @@ "default": 0.3, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_RATT_TH", @@ -8252,8 +8252,8 @@ "default": 0.8, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MC_ROLLRATE_D", @@ -8265,8 +8265,8 @@ "default": 0.003, "increment": 0.0005, "decimalPlaces": 4, - "minValue": 0, - "maxValue": 0.01 + "min": 0, + "max": 0.01 }, { "name": "MC_ROLLRATE_FF", @@ -8277,8 +8277,8 @@ "longDesc": "Improves tracking performance.", "default": 0, "decimalPlaces": 4, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_ROLLRATE_I", @@ -8290,8 +8290,8 @@ "default": 0.2, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_ROLLRATE_K", @@ -8303,8 +8303,8 @@ "default": 1, "increment": 0.0005, "decimalPlaces": 4, - "minValue": 0.01, - "maxValue": 5 + "min": 0.01, + "max": 5 }, { "name": "MC_ROLLRATE_MAX", @@ -8317,8 +8317,8 @@ "default": 220, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 1800 + "min": 0, + "max": 1800 }, { "name": "MC_ROLLRATE_P", @@ -8330,8 +8330,8 @@ "default": 0.15, "increment": 0.01, "decimalPlaces": 3, - "minValue": 0.01, - "maxValue": 0.5 + "min": 0.01, + "max": 0.5 }, { "name": "MC_ROLL_P", @@ -8344,8 +8344,8 @@ "default": 6.5, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 12 + "min": 0, + "max": 12 }, { "name": "MC_RR_INT_LIM", @@ -8357,8 +8357,8 @@ "default": 0.3, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_YAWRATE_D", @@ -8370,8 +8370,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_YAWRATE_FF", @@ -8383,8 +8383,8 @@ "default": 0, "increment": 0.01, "decimalPlaces": 4, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_YAWRATE_I", @@ -8396,8 +8396,8 @@ "default": 0.1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MC_YAWRATE_K", @@ -8409,8 +8409,8 @@ "default": 1, "increment": 0.0005, "decimalPlaces": 4, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "MC_YAWRATE_MAX", @@ -8422,8 +8422,8 @@ "default": 200, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 1800 + "min": 0, + "max": 1800 }, { "name": "MC_YAWRATE_P", @@ -8435,8 +8435,8 @@ "default": 0.2, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 0.6 + "min": 0, + "max": 0.6 }, { "name": "MC_YAW_P", @@ -8449,8 +8449,8 @@ "default": 2.8, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "MC_YAW_WEIGHT", @@ -8463,8 +8463,8 @@ "default": 0.4, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MC_YR_INT_LIM", @@ -8476,8 +8476,8 @@ "default": 0.3, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MIS_ALTMODE", @@ -8498,8 +8498,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MIS_DIST_1WP", @@ -8512,8 +8512,8 @@ "default": 900, "increment": 100, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 10000 + "min": 0, + "max": 10000 }, { "name": "MIS_DIST_WPS", @@ -8526,8 +8526,8 @@ "default": 900, "increment": 100, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 10000 + "min": 0, + "max": 10000 }, { "name": "MIS_LTRMIN_ALT", @@ -8540,8 +8540,8 @@ "default": -1, "increment": 0.5, "decimalPlaces": 1, - "minValue": -1, - "maxValue": 80 + "min": -1, + "max": 80 }, { "name": "MIS_MNT_YAW_CTL", @@ -8562,8 +8562,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MIS_TAKEOFF_ALT", @@ -8576,8 +8576,8 @@ "default": 2.5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 80 + "min": 0, + "max": 80 }, { "name": "MIS_TAKEOFF_REQ", @@ -8588,8 +8588,8 @@ "longDesc": "If set, the mission feasibility checker will check for a takeoff waypoint on the mission.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MIS_YAW_ERR", @@ -8601,8 +8601,8 @@ "default": 12, "increment": 1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "MIS_YAW_TMT", @@ -8615,8 +8615,8 @@ "default": -1, "increment": 1, "decimalPlaces": 1, - "minValue": -1, - "maxValue": 20 + "min": -1, + "max": 20 }, { "name": "MKBLCTRL_TEST", @@ -8626,8 +8626,8 @@ "shortDesc": "Test mode (Identify) of MKBLCTRL Driver", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MNT_DO_STAB", @@ -8637,8 +8637,8 @@ "shortDesc": "Stabilize the mount (set to true for servo gimbal, false for passthrough). Does not affect MAVLINK_ROI input", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MNT_MAN_PITCH", @@ -8678,8 +8678,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 6 + "min": 0, + "max": 6 }, { "name": "MNT_MAN_ROLL", @@ -8719,8 +8719,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 6 + "min": 0, + "max": 6 }, { "name": "MNT_MAN_YAW", @@ -8760,8 +8760,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 6 + "min": 0, + "max": 6 }, { "name": "MNT_MAV_COMPID", @@ -8772,8 +8772,8 @@ "longDesc": "If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this component ID.", "default": 154, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MNT_MAV_SYSID", @@ -8784,8 +8784,8 @@ "longDesc": "If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this target ID.", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MNT_MODE_IN", @@ -8819,8 +8819,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 3 + "min": -1, + "max": 3 }, { "name": "MNT_MODE_OUT", @@ -8841,8 +8841,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MNT_OB_LOCK_MODE", @@ -8852,8 +8852,8 @@ "shortDesc": "Mixer value for selecting a locking mode if required for the gimbal (only in AUX output mode)", "default": 0, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 1 + "min": -1, + "max": 1 }, { "name": "MNT_OB_NORM_MODE", @@ -8863,8 +8863,8 @@ "shortDesc": "Mixer value for selecting normal mode if required by the gimbal (only in AUX output mode)", "default": -1, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 1 + "min": -1, + "max": 1 }, { "name": "MNT_OFF_PITCH", @@ -8874,8 +8874,8 @@ "shortDesc": "Offset for pitch channel output in degrees", "default": 0, "decimalPlaces": 1, - "minValue": -360, - "maxValue": 360 + "min": -360, + "max": 360 }, { "name": "MNT_OFF_ROLL", @@ -8885,8 +8885,8 @@ "shortDesc": "Offset for roll channel output in degrees", "default": 0, "decimalPlaces": 1, - "minValue": -360, - "maxValue": 360 + "min": -360, + "max": 360 }, { "name": "MNT_OFF_YAW", @@ -8896,8 +8896,8 @@ "shortDesc": "Offset for yaw channel output in degrees", "default": 0, "decimalPlaces": 1, - "minValue": -360, - "maxValue": 360 + "min": -360, + "max": 360 }, { "name": "MNT_RANGE_PITCH", @@ -8907,8 +8907,8 @@ "shortDesc": "Range of pitch channel output in degrees (only in AUX output mode)", "default": 360, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 720 + "min": 1, + "max": 720 }, { "name": "MNT_RANGE_ROLL", @@ -8918,8 +8918,8 @@ "shortDesc": "Range of roll channel output in degrees (only in AUX output mode)", "default": 360, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 720 + "min": 1, + "max": 720 }, { "name": "MNT_RANGE_YAW", @@ -8929,8 +8929,8 @@ "shortDesc": "Range of yaw channel output in degrees (only in AUX output mode)", "default": 360, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 720 + "min": 1, + "max": 720 }, { "name": "MOT_ORDERING", @@ -8951,8 +8951,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MOT_POLE_COUNT", @@ -8963,8 +8963,8 @@ "longDesc": "Specify the number of magnetic poles of the motors. It is required to compute the RPM value from the eRPM returned with the ESC telemetry. Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). Typical motors for 5 inch props have 14 poles.", "default": 14, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MOT_SLEW_MAX", @@ -8976,8 +8976,8 @@ "units": "s/(1000*PWM)", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MPC_ACC_DOWN_MAX", @@ -8989,8 +8989,8 @@ "default": 3, "increment": 1, "decimalPlaces": 2, - "minValue": 2, - "maxValue": 15 + "min": 2, + "max": 15 }, { "name": "MPC_ACC_HOR", @@ -9003,8 +9003,8 @@ "default": 3, "increment": 1, "decimalPlaces": 2, - "minValue": 2, - "maxValue": 15 + "min": 2, + "max": 15 }, { "name": "MPC_ACC_HOR_MAX", @@ -9017,8 +9017,8 @@ "default": 5, "increment": 1, "decimalPlaces": 2, - "minValue": 2, - "maxValue": 15 + "min": 2, + "max": 15 }, { "name": "MPC_ACC_UP_MAX", @@ -9030,8 +9030,8 @@ "default": 4, "increment": 1, "decimalPlaces": 2, - "minValue": 2, - "maxValue": 15 + "min": 2, + "max": 15 }, { "name": "MPC_ALT_MODE", @@ -9056,8 +9056,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "MPC_DEC_HOR_SLOW", @@ -9070,8 +9070,8 @@ "default": 5, "increment": 1, "decimalPlaces": 2, - "minValue": 0.5, - "maxValue": 10 + "min": 0.5, + "max": 10 }, { "name": "MPC_HOLD_DZ", @@ -9081,8 +9081,8 @@ "shortDesc": "Deadzone of sticks where position hold is enabled", "default": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_HOLD_MAX_XY", @@ -9093,8 +9093,8 @@ "units": "m/s", "default": 0.8, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3 + "min": 0, + "max": 3 }, { "name": "MPC_HOLD_MAX_Z", @@ -9105,8 +9105,8 @@ "units": "m/s", "default": 0.6, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 3 + "min": 0, + "max": 3 }, { "name": "MPC_JERK_AUTO", @@ -9119,8 +9119,8 @@ "default": 4, "increment": 1, "decimalPlaces": 1, - "minValue": 1, - "maxValue": 80 + "min": 1, + "max": 80 }, { "name": "MPC_JERK_MAX", @@ -9133,8 +9133,8 @@ "default": 8, "increment": 1, "decimalPlaces": 2, - "minValue": 0.5, - "maxValue": 500 + "min": 0.5, + "max": 500 }, { "name": "MPC_JERK_MIN", @@ -9147,8 +9147,8 @@ "default": 8, "increment": 1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 30 + "min": 0, + "max": 30 }, { "name": "MPC_LAND_ALT1", @@ -9160,8 +9160,8 @@ "units": "m", "default": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 122 + "min": 0, + "max": 122 }, { "name": "MPC_LAND_ALT2", @@ -9173,8 +9173,8 @@ "units": "m", "default": 2, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 122 + "min": 0, + "max": 122 }, { "name": "MPC_LAND_RC_HELP", @@ -9194,8 +9194,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_LAND_SPEED", @@ -9206,8 +9206,8 @@ "units": "m/s", "default": 0.7, "decimalPlaces": 1, - "minValue": 0.6, - "maxValue": 3.40282e+38 + "min": 0.6, + "max": 3.40282e+38 }, { "name": "MPC_LAND_VEL_XY", @@ -9218,8 +9218,8 @@ "units": "m/s", "default": 10, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 3.40282e+38 + "min": 0, + "max": 3.40282e+38 }, { "name": "MPC_MANTHR_MIN", @@ -9232,8 +9232,8 @@ "default": 0.08, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_MAN_TILT_MAX", @@ -9244,8 +9244,8 @@ "units": "deg", "default": 35, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 90 + "min": 0, + "max": 90 }, { "name": "MPC_MAN_Y_MAX", @@ -9256,8 +9256,8 @@ "units": "deg/s", "default": 150, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 400 + "min": 0, + "max": 400 }, { "name": "MPC_MAN_Y_TAU", @@ -9268,8 +9268,8 @@ "units": "s", "default": 0.08, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "MPC_POS_MODE", @@ -9294,8 +9294,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MPC_SPOOLUP_TIME", @@ -9307,8 +9307,8 @@ "units": "s", "default": 1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "MPC_THR_CURVE", @@ -9329,8 +9329,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MPC_THR_HOVER", @@ -9343,8 +9343,8 @@ "default": 0.5, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0.1, - "maxValue": 0.8 + "min": 0.1, + "max": 0.8 }, { "name": "MPC_THR_MAX", @@ -9357,8 +9357,8 @@ "default": 1, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_THR_MIN", @@ -9371,8 +9371,8 @@ "default": 0.12, "increment": 0.01, "decimalPlaces": 2, - "minValue": 0.05, - "maxValue": 1 + "min": 0.05, + "max": 1 }, { "name": "MPC_TILTMAX_AIR", @@ -9384,8 +9384,8 @@ "units": "deg", "default": 45, "decimalPlaces": 1, - "minValue": 20, - "maxValue": 89 + "min": 20, + "max": 89 }, { "name": "MPC_TILTMAX_LND", @@ -9397,8 +9397,8 @@ "units": "deg", "default": 12, "decimalPlaces": 1, - "minValue": 10, - "maxValue": 89 + "min": 10, + "max": 89 }, { "name": "MPC_TKO_RAMP_T", @@ -9409,8 +9409,8 @@ "longDesc": "Increasing this value will make automatic and manual takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp", "default": 3, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 5 + "min": 0, + "max": 5 }, { "name": "MPC_TKO_SPEED", @@ -9421,8 +9421,8 @@ "units": "m/s", "default": 1.5, "decimalPlaces": 2, - "minValue": 1, - "maxValue": 5 + "min": 1, + "max": 5 }, { "name": "MPC_USE_HTE", @@ -9433,8 +9433,8 @@ "longDesc": "Set false to use the fixed parameter MPC_THR_HOVER Set true to use the value computed by the hover thrust estimator", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "MPC_VELD_LP", @@ -9445,8 +9445,8 @@ "units": "Hz", "default": 5, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "MPC_VEL_MANUAL", @@ -9458,8 +9458,8 @@ "default": 10, "increment": 1, "decimalPlaces": 2, - "minValue": 3, - "maxValue": 20 + "min": 3, + "max": 20 }, { "name": "MPC_XY_CRUISE", @@ -9472,8 +9472,8 @@ "default": 5, "increment": 1, "decimalPlaces": 2, - "minValue": 3, - "maxValue": 20 + "min": 3, + "max": 20 }, { "name": "MPC_XY_MAN_EXPO", @@ -9484,8 +9484,8 @@ "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve", "default": 0.6, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_XY_P", @@ -9495,8 +9495,8 @@ "shortDesc": "Proportional gain for horizontal position error", "default": 0.95, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "MPC_XY_TRAJ_P", @@ -9506,8 +9506,8 @@ "shortDesc": "Proportional gain for horizontal trajectory position error", "default": 0.5, "decimalPlaces": 1, - "minValue": 0.1, - "maxValue": 1 + "min": 0.1, + "max": 1 }, { "name": "MPC_XY_VEL_D_ACC", @@ -9518,8 +9518,8 @@ "longDesc": "defined as correction acceleration in m/s^2 per m/s^2 velocity derivative", "default": 0.2, "decimalPlaces": 3, - "minValue": 0.1, - "maxValue": 2 + "min": 0.1, + "max": 2 }, { "name": "MPC_XY_VEL_I_ACC", @@ -9530,8 +9530,8 @@ "longDesc": "defined as correction acceleration in m/s^2 per m velocity integral Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind.", "default": 0.4, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 60 + "min": 0, + "max": 60 }, { "name": "MPC_XY_VEL_MAX", @@ -9544,8 +9544,8 @@ "default": 12, "increment": 1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 20 + "min": 0, + "max": 20 }, { "name": "MPC_XY_VEL_P_ACC", @@ -9556,8 +9556,8 @@ "longDesc": "defined as correction acceleration in m/s^2 per m/s velocity error", "default": 1.8, "decimalPlaces": 2, - "minValue": 1.2, - "maxValue": 3 + "min": 1.2, + "max": 3 }, { "name": "MPC_YAWRAUTO_MAX", @@ -9570,8 +9570,8 @@ "default": 45, "increment": 5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 360 + "min": 0, + "max": 360 }, { "name": "MPC_YAW_EXPO", @@ -9582,8 +9582,8 @@ "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve", "default": 0.6, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_YAW_MODE", @@ -9616,8 +9616,8 @@ } ], "decimalPlaces": 3, - "minValue": 0, - "maxValue": 4 + "min": 0, + "max": 4 }, { "name": "MPC_Z_MAN_EXPO", @@ -9628,8 +9628,8 @@ "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve", "default": 0.6, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "MPC_Z_P", @@ -9639,8 +9639,8 @@ "shortDesc": "Proportional gain for vertical position error", "default": 1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1.5 + "min": 0, + "max": 1.5 }, { "name": "MPC_Z_VEL_D_ACC", @@ -9651,8 +9651,8 @@ "longDesc": "defined as correction acceleration in m/s^2 per m/s^2 velocity derivative", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2 + "min": 0, + "max": 2 }, { "name": "MPC_Z_VEL_I_ACC", @@ -9663,8 +9663,8 @@ "longDesc": "defined as correction acceleration in m/s^2 per m velocity integral Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.", "default": 2, "decimalPlaces": 3, - "minValue": 0.2, - "maxValue": 2 + "min": 0.2, + "max": 2 }, { "name": "MPC_Z_VEL_MAX_DN", @@ -9676,8 +9676,8 @@ "units": "m/s", "default": 1, "decimalPlaces": 3, - "minValue": 0.5, - "maxValue": 4 + "min": 0.5, + "max": 4 }, { "name": "MPC_Z_VEL_MAX_UP", @@ -9689,8 +9689,8 @@ "units": "m/s", "default": 3, "decimalPlaces": 1, - "minValue": 0.5, - "maxValue": 8 + "min": 0.5, + "max": 8 }, { "name": "MPC_Z_VEL_P_ACC", @@ -9701,8 +9701,8 @@ "longDesc": "defined as correction acceleration in m/s^2 per m/s velocity error", "default": 4, "decimalPlaces": 2, - "minValue": 2, - "maxValue": 8 + "min": 2, + "max": 8 }, { "name": "NAV_ACC_RAD", @@ -9715,8 +9715,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0.05, - "maxValue": 200 + "min": 0.05, + "max": 200 }, { "name": "NAV_AH_ALT", @@ -9729,8 +9729,8 @@ "default": 600, "increment": 0.5, "decimalPlaces": 1, - "minValue": -50, - "maxValue": 3.40282e+38 + "min": -50, + "max": 3.40282e+38 }, { "name": "NAV_AH_LAT", @@ -9742,8 +9742,8 @@ "units": "deg * 1e7", "default": -2.65848e+08, "decimalPlaces": 3, - "minValue": -9e+08, - "maxValue": 9e+08 + "min": -9e+08, + "max": 9e+08 }, { "name": "NAV_AH_LON", @@ -9755,8 +9755,8 @@ "units": "deg * 1e7", "default": 1.51842e+09, "decimalPlaces": 3, - "minValue": -1.8e+09, - "maxValue": 1.8e+09 + "min": -1.8e+09, + "max": 1.8e+09 }, { "name": "NAV_DLL_ACT", @@ -9793,8 +9793,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "NAV_FORCE_VT", @@ -9804,8 +9804,8 @@ "shortDesc": "Force VTOL mode takeoff and land", "default": 1, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "NAV_FT_DST", @@ -9817,8 +9817,8 @@ "units": "meters", "default": 8, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 3.40282e+38 + "min": 1, + "max": 3.40282e+38 }, { "name": "NAV_FT_FS", @@ -9830,8 +9830,8 @@ "units": "n/a", "default": 1, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 3 + "min": 0, + "max": 3 }, { "name": "NAV_FT_RS", @@ -9842,8 +9842,8 @@ "units": "n/a", "default": 0.5, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "NAV_FW_ALTL_RAD", @@ -9855,8 +9855,8 @@ "units": "m", "default": 5, "decimalPlaces": 1, - "minValue": 0.05, - "maxValue": 200 + "min": 0.05, + "max": 200 }, { "name": "NAV_FW_ALT_RAD", @@ -9869,8 +9869,8 @@ "default": 10, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0.05, - "maxValue": 200 + "min": 0.05, + "max": 200 }, { "name": "NAV_GPSF_LT", @@ -9883,8 +9883,8 @@ "default": 0, "increment": 1, "decimalPlaces": 0, - "minValue": 0, - "maxValue": 3600 + "min": 0, + "max": 3600 }, { "name": "NAV_GPSF_P", @@ -9897,8 +9897,8 @@ "default": 0, "increment": 0.5, "decimalPlaces": 1, - "minValue": -30, - "maxValue": 30 + "min": -30, + "max": 30 }, { "name": "NAV_GPSF_R", @@ -9911,8 +9911,8 @@ "default": 15, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 30 + "min": 0, + "max": 30 }, { "name": "NAV_GPSF_TR", @@ -9925,8 +9925,8 @@ "default": 0, "increment": 0.05, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 1 + "min": 0, + "max": 1 }, { "name": "NAV_LOITER_RAD", @@ -9939,8 +9939,8 @@ "default": 50, "increment": 0.5, "decimalPlaces": 1, - "minValue": 25, - "maxValue": 1000 + "min": 25, + "max": 1000 }, { "name": "NAV_MC_ALT_RAD", @@ -9953,8 +9953,8 @@ "default": 0.8, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0.05, - "maxValue": 200 + "min": 0.05, + "max": 200 }, { "name": "NAV_MIN_FT_HT", @@ -9966,8 +9966,8 @@ "units": "meters", "default": 8, "decimalPlaces": 3, - "minValue": 8, - "maxValue": 3.40282e+38 + "min": 8, + "max": 3.40282e+38 }, { "name": "NAV_RCL_ACT", @@ -10004,8 +10004,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "NAV_TRAFF_AVOID", @@ -10038,8 +10038,8 @@ } ], "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "NAV_TRAFF_A_RADM", @@ -10051,8 +10051,8 @@ "units": "m", "default": 500, "decimalPlaces": 3, - "minValue": 500, - "maxValue": 3.40282e+38 + "min": 500, + "max": 3.40282e+38 }, { "name": "NAV_TRAFF_A_RADU", @@ -10064,8 +10064,8 @@ "units": "m", "default": 10, "decimalPlaces": 3, - "minValue": 10, - "maxValue": 500 + "min": 10, + "max": 500 }, { "name": "OSD_ATXXXX_CFG", @@ -10091,8 +10091,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PCF8583_ADDR", @@ -10113,8 +10113,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PCF8583_MAGNET", @@ -10126,8 +10126,8 @@ "default": 2, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 2.14748e+09 + "min": 1, + "max": 2.14748e+09 }, { "name": "PCF8583_POOL", @@ -10139,8 +10139,8 @@ "default": 1e+06, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PCF8583_RESET", @@ -10152,8 +10152,8 @@ "default": 500000, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PLD_BTOUT", @@ -10166,8 +10166,8 @@ "default": 5, "increment": 0.5, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 50 + "min": 0, + "max": 50 }, { "name": "PLD_FAPPR_ALT", @@ -10180,8 +10180,8 @@ "default": 0.1, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "PLD_HACC_RAD", @@ -10194,8 +10194,8 @@ "default": 0.2, "increment": 0.1, "decimalPlaces": 2, - "minValue": 0, - "maxValue": 10 + "min": 0, + "max": 10 }, { "name": "PLD_MAX_SRCH", @@ -10206,8 +10206,8 @@ "longDesc": "Maximum number of times to seach for the landing target if it is lost during the precision landing.", "default": 3, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "PLD_SRCH_ALT", @@ -10220,8 +10220,8 @@ "default": 10, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "PLD_SRCH_TOUT", @@ -10234,8 +10234,8 @@ "default": 10, "increment": 0.1, "decimalPlaces": 1, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "PWM_AUX_DIS1", @@ -10248,8 +10248,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS2", @@ -10262,8 +10262,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS3", @@ -10276,8 +10276,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS4", @@ -10290,8 +10290,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS5", @@ -10304,8 +10304,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS6", @@ -10318,8 +10318,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS7", @@ -10332,8 +10332,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DIS8", @@ -10346,8 +10346,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_DISARMED", @@ -10360,8 +10360,8 @@ "default": 1500, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2200 + "min": 0, + "max": 2200 }, { "name": "PWM_AUX_FAIL1", @@ -10374,8 +10374,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL2", @@ -10388,8 +10388,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL3", @@ -10402,8 +10402,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL4", @@ -10416,8 +10416,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL5", @@ -10430,8 +10430,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL6", @@ -10444,8 +10444,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL7", @@ -10458,8 +10458,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_FAIL8", @@ -10472,8 +10472,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX", @@ -10486,8 +10486,8 @@ "default": 2000, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1600, - "maxValue": 2200 + "min": 1600, + "max": 2200 }, { "name": "PWM_AUX_MAX1", @@ -10500,8 +10500,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX2", @@ -10514,8 +10514,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX3", @@ -10528,8 +10528,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX4", @@ -10542,8 +10542,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX5", @@ -10556,8 +10556,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX6", @@ -10570,8 +10570,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX7", @@ -10584,8 +10584,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MAX8", @@ -10598,8 +10598,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN", @@ -10612,8 +10612,8 @@ "default": 1000, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 800, - "maxValue": 1400 + "min": 800, + "max": 1400 }, { "name": "PWM_AUX_MIN1", @@ -10626,8 +10626,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN2", @@ -10640,8 +10640,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN3", @@ -10654,8 +10654,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN4", @@ -10668,8 +10668,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN5", @@ -10682,8 +10682,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN6", @@ -10696,8 +10696,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN7", @@ -10710,8 +10710,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_MIN8", @@ -10724,8 +10724,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_AUX_RATE", @@ -10738,8 +10738,8 @@ "default": 50, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2000 + "min": -1, + "max": 2000 }, { "name": "PWM_AUX_REV1", @@ -10750,8 +10750,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV2", @@ -10762,8 +10762,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV3", @@ -10774,8 +10774,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV4", @@ -10786,8 +10786,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV5", @@ -10798,8 +10798,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV6", @@ -10810,8 +10810,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV7", @@ -10822,8 +10822,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_REV8", @@ -10834,8 +10834,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_AUX_TRIM1", @@ -10846,8 +10846,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM2", @@ -10858,8 +10858,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM3", @@ -10870,8 +10870,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM4", @@ -10882,8 +10882,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM5", @@ -10894,8 +10894,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM6", @@ -10906,8 +10906,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM7", @@ -10918,8 +10918,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_AUX_TRIM8", @@ -10930,8 +10930,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_DISARMED", @@ -10944,8 +10944,8 @@ "default": 900, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2200 + "min": 0, + "max": 2200 }, { "name": "PWM_MAIN_DIS1", @@ -10958,8 +10958,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS2", @@ -10972,8 +10972,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS3", @@ -10986,8 +10986,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS4", @@ -11000,8 +11000,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS5", @@ -11014,8 +11014,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS6", @@ -11028,8 +11028,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS7", @@ -11042,8 +11042,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_DIS8", @@ -11056,8 +11056,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL1", @@ -11070,8 +11070,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL2", @@ -11084,8 +11084,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL3", @@ -11098,8 +11098,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL4", @@ -11112,8 +11112,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL5", @@ -11126,8 +11126,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL6", @@ -11140,8 +11140,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL7", @@ -11154,8 +11154,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_FAIL8", @@ -11168,8 +11168,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX1", @@ -11182,8 +11182,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX2", @@ -11196,8 +11196,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX3", @@ -11210,8 +11210,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX4", @@ -11224,8 +11224,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX5", @@ -11238,8 +11238,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX6", @@ -11252,8 +11252,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX7", @@ -11266,8 +11266,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MAX8", @@ -11280,8 +11280,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN1", @@ -11294,8 +11294,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN2", @@ -11308,8 +11308,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN3", @@ -11322,8 +11322,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN4", @@ -11336,8 +11336,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN5", @@ -11350,8 +11350,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN6", @@ -11364,8 +11364,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN7", @@ -11378,8 +11378,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_MIN8", @@ -11392,8 +11392,8 @@ "default": -1, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2200 + "min": -1, + "max": 2200 }, { "name": "PWM_MAIN_REV1", @@ -11404,8 +11404,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV2", @@ -11416,8 +11416,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV3", @@ -11428,8 +11428,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV4", @@ -11440,8 +11440,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV5", @@ -11452,8 +11452,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV6", @@ -11464,8 +11464,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV7", @@ -11476,8 +11476,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_REV8", @@ -11488,8 +11488,8 @@ "longDesc": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "PWM_MAIN_TRIM1", @@ -11500,8 +11500,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM2", @@ -11512,8 +11512,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM3", @@ -11524,8 +11524,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM4", @@ -11536,8 +11536,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM5", @@ -11548,8 +11548,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM6", @@ -11560,8 +11560,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM7", @@ -11572,8 +11572,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAIN_TRIM8", @@ -11584,8 +11584,8 @@ "longDesc": "Set to normalized offset", "default": 0, "decimalPlaces": 2, - "minValue": -0.2, - "maxValue": 0.2 + "min": -0.2, + "max": 0.2 }, { "name": "PWM_MAX", @@ -11598,8 +11598,8 @@ "default": 2000, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 1600, - "maxValue": 2200 + "min": 1600, + "max": 2200 }, { "name": "PWM_MIN", @@ -11612,8 +11612,8 @@ "default": 1000, "rebootRequired": true, "decimalPlaces": 3, - "minValue": 800, - "maxValue": 1400 + "min": 800, + "max": 1400 }, { "name": "PWM_RATE", @@ -11626,8 +11626,8 @@ "default": 400, "rebootRequired": true, "decimalPlaces": 3, - "minValue": -1, - "maxValue": 2000 + "min": -1, + "max": 2000 }, { "name": "PWM_SBUS_MODE", @@ -11638,8 +11638,8 @@ "longDesc": "Set to 1 to enable S.BUS version 1 output instead of RSSI.", "default": 0, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "RBCLW_ADDRESS", @@ -11684,8 +11684,8 @@ } ], "decimalPlaces": 3, - "minValue": 128, - "maxValue": 135 + "min": 128, + "max": 135 }, { "name": "RBCLW_BAUD", @@ -11731,8 +11731,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": 2400, - "maxValue": 460800 + "min": 2400, + "max": 460800 }, { "name": "RBCLW_COUNTS_REV", @@ -11743,8 +11743,8 @@ "longDesc": "Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover.", "default": 1200, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 2.14748e+09 + "min": 1, + "max": 2.14748e+09 }, { "name": "RBCLW_READ_PER", @@ -11756,8 +11756,8 @@ "units": "ms", "default": 10, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 1000 + "min": 1, + "max": 1000 }, { "name": "RBCLW_SER_CFG", @@ -11811,8 +11811,8 @@ ], "rebootRequired": true, "decimalPlaces": 3, - "minValue": -2.14748e+09, - "maxValue": 2.14748e+09 + "min": -2.14748e+09, + "max": 2.14748e+09 }, { "name": "RBCLW_WRITE_PER", @@ -11824,8 +11824,8 @@ "units": "ms", "default": 10, "decimalPlaces": 3, - "minValue": 1, - "maxValue": 1000 + "min": 1, + "max": 1000 }, { "name": "RC{n}_DZ", @@ -11836,8 +11836,8 @@ "longDesc": "The +- range of this value around the trim value will be considered as zero.", "default": 0, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 100 + "min": 0, + "max": 100 }, { "name": "RC{n}_MAX", @@ -11849,8 +11849,8 @@ "units": "us", "default": 2000, "decimalPlaces": 3, - "minValue": 1500, - "maxValue": 2200 + "min": 1500, + "max": 2200 }, { "name": "RC{n}_MIN", @@ -11862,8 +11862,8 @@ "units": "us", "default": 1000, "decimalPlaces": 3, - "minValue": 800, - "maxValue": 1500 + "min": 800, + "max": 1500 }, { "name": "RC{n}_REV", @@ -11884,8 +11884,8 @@ } ], "decimalPlaces": 3, - "minValue": -1, - "maxValue": 1 + "min": -1, + "max": 1 }, { "name": "RC{n}_TRIM", @@ -11897,8 +11897,8 @@ "units": "us", "default": 1500, "decimalPlaces": 3, - "minValue": 800, - "maxValue": 2200 + "min": 800, + "max": 2200 }, { "name": "RC_ACRO_TH", @@ -11909,8 +11909,8 @@ "longDesc": "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 channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel 0", "default": 1000, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2000 + "min": 0, + "max": 2000 }, { "name": "RC_RSSI_PWM_MIN", @@ -14830,8 +14830,8 @@ "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "default": 2000, "decimalPlaces": 3, - "minValue": 0, - "maxValue": 2000 + "min": 0, + "max": 2000 }, { "name": "RC_STAB_TH", @@ -14842,8 +14842,8 @@ "longDesc": "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 channelth negative : true when channelhdr.offset; - + while (burstOffset < _currentFile.size() && burstCount++ < burstMax) { _currentFile.seek(burstOffset); @@ -231,7 +231,10 @@ void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderCompon burstOffset += cBytes; } - _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile); + if (burstOffset >= _currentFile.size()) { + // Burst is fully complete + _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile); + } } void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber) @@ -352,7 +355,7 @@ void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, ui ackResponse.hdr.opcode = MavlinkFTP::kRspAck; ackResponse.hdr.req_opcode = reqOpcode; - ackResponse.hdr.session = 0; + ackResponse.hdr.session = _sessionId; ackResponse.hdr.size = 0; _sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber); @@ -364,7 +367,7 @@ void MockLinkFTP::_sendNak(uint8_t targetSystemId, uint8_t targetComponentId, Ma nakResponse.hdr.opcode = MavlinkFTP::kRspNak; nakResponse.hdr.req_opcode = reqOpcode; - nakResponse.hdr.session = 0; + nakResponse.hdr.session = _sessionId; nakResponse.hdr.size = 1; nakResponse.data[0] = error; @@ -377,7 +380,7 @@ void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentI nakResponse.hdr.opcode = MavlinkFTP::kRspNak; nakResponse.hdr.req_opcode = reqOpcode; - nakResponse.hdr.session = 0; + nakResponse.hdr.session = _sessionId; nakResponse.hdr.size = 2; nakResponse.data[0] = MavlinkFTP::kErrFailErrno; nakResponse.data[1] = nakErrno; -- 2.22.0